mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: add accessors for turtle mode
This commit is contained in:
parent
00cc8a4042
commit
513aa592e4
|
@ -73,6 +73,8 @@ public:
|
|||
// return the roll factor of any motor, this is used for tilt rotors and tail sitters
|
||||
// using copter motors for forward flight
|
||||
float get_roll_factor(uint8_t i) override { return _roll_factor[i]; }
|
||||
// return the pitch factor of any motor
|
||||
float get_pitch_factor(uint8_t i) override { return _pitch_factor[i]; }
|
||||
|
||||
const char* get_frame_string() const override { return _frame_class_string; }
|
||||
const char* get_type_string() const override { return _frame_type_string; }
|
||||
|
|
|
@ -100,6 +100,9 @@ public:
|
|||
// as vectoring is used for yaw control
|
||||
virtual void disable_yaw_torque(void) {}
|
||||
|
||||
// return whether a motor is enabled or not
|
||||
bool is_motor_enabled(uint8_t i) override { return motor_enabled[i]; }
|
||||
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
|
|
@ -209,6 +209,12 @@ public:
|
|||
// using copter motors for forward flight
|
||||
virtual float get_roll_factor(uint8_t i) { return 0.0f; }
|
||||
|
||||
// return the pitch factor of any motor
|
||||
virtual float get_pitch_factor(uint8_t i) { return 0.0f; }
|
||||
|
||||
// return whether a motor is enabled or not
|
||||
virtual bool is_motor_enabled(uint8_t i) { return false; }
|
||||
|
||||
// This function required for tradheli. Tradheli initializes targets when going from unarmed to armed state.
|
||||
// This function is overriden in motors_heli class. Always true for multicopters.
|
||||
virtual bool init_targets_on_arming() const { return true; }
|
||||
|
@ -226,10 +232,12 @@ public:
|
|||
|
||||
MAV_TYPE get_frame_mav_type() const { return _mav_type; }
|
||||
|
||||
// direct motor write
|
||||
virtual void rc_write(uint8_t chan, uint16_t pwm);
|
||||
|
||||
protected:
|
||||
// output functions that should be overloaded by child classes
|
||||
virtual void output_armed_stabilizing() = 0;
|
||||
virtual void rc_write(uint8_t chan, uint16_t pwm);
|
||||
virtual void rc_write_angle(uint8_t chan, int16_t angle_cd);
|
||||
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz);
|
||||
|
||||
|
|
Loading…
Reference in New Issue