2013-05-29 20:51:34 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
/// @file AP_MotorsTri.h
|
|
|
|
/// @brief Motor control class for Tricopters
|
|
|
|
|
2012-10-26 20:59:07 -03:00
|
|
|
#ifndef __AP_MOTORS_TRI_H__
|
|
|
|
#define __AP_MOTORS_TRI_H__
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
#include <AP_Common.h>
|
|
|
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
|
|
|
#include <RC_Channel.h> // RC Channel Library
|
2012-10-26 20:59:07 -03:00
|
|
|
#include "AP_Motors.h"
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
// tail servo uses channel 7
|
2012-08-17 03:20:27 -03:00
|
|
|
#define AP_MOTORS_CH_TRI_YAW CH_7
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// @class AP_MotorsTri
|
|
|
|
class AP_MotorsTri : public AP_Motors {
|
|
|
|
public:
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// Constructor
|
2013-01-02 00:27:58 -04:00
|
|
|
AP_MotorsTri( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, RC_Channel* rc_tail, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
|
|
|
AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
|
2012-08-17 03:20:27 -03:00
|
|
|
_rc_tail(rc_tail) {
|
|
|
|
};
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// init
|
2013-05-14 05:35:27 -03:00
|
|
|
virtual void Init();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-09-13 09:31:13 -03:00
|
|
|
// set update rate to motors - a value in hertz
|
2013-05-14 05:35:27 -03:00
|
|
|
void set_update_rate( uint16_t speed_hz );
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// enable - starts allowing signals to be sent to motors
|
2013-05-14 05:35:27 -03:00
|
|
|
virtual void enable();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// motor test
|
|
|
|
virtual void output_test();
|
|
|
|
|
|
|
|
// output_min - sends minimum values out to the motors
|
|
|
|
virtual void output_min();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
protected:
|
2012-08-17 03:20:27 -03:00
|
|
|
// output - sends commands to the motors
|
|
|
|
virtual void output_armed();
|
|
|
|
virtual void output_disarmed();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
RC_Channel* _rc_tail; // REV parameter used from this channel to determine direction of tail servo movement
|
|
|
|
};
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-10-26 20:59:07 -03:00
|
|
|
#endif // AP_MOTORSTRI
|