mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Motors: fixed typos
This commit is contained in:
parent
cb858d2c99
commit
bc7488e2f2
@ -125,7 +125,7 @@ public:
|
||||
// supports_yaw_passthrough
|
||||
virtual bool supports_yaw_passthrough() const { return false; }
|
||||
|
||||
float get_throttle_hover() const { return 0.5f; };
|
||||
float get_throttle_hover() const { return 0.5f; }
|
||||
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
@ -51,7 +51,7 @@ public:
|
||||
|
||||
// update estimated throttle required to hover
|
||||
void update_throttle_hover(float dt);
|
||||
virtual float get_throttle_hover() const { return _throttle_hover; };
|
||||
virtual float get_throttle_hover() const { return _throttle_hover; }
|
||||
|
||||
// spool up states
|
||||
enum spool_up_down_mode {
|
||||
|
@ -43,20 +43,20 @@ public:
|
||||
AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
||||
|
||||
// set update rate to motors - a value in hertz
|
||||
virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; };
|
||||
virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; }
|
||||
|
||||
// set frame orientation (normally + or X)
|
||||
virtual void set_frame_orientation( uint8_t new_orientation ) { _flags.frame_orientation = new_orientation; };
|
||||
virtual void set_frame_orientation( uint8_t new_orientation ) { _flags.frame_orientation = new_orientation; }
|
||||
|
||||
// arm, disarm or check status status of motors
|
||||
bool armed() const { return _flags.armed; };
|
||||
bool armed() const { return _flags.armed; }
|
||||
void armed(bool arm);
|
||||
|
||||
// set motor interlock status
|
||||
void set_interlock(bool set) { _flags.interlock = set;}
|
||||
|
||||
// get motor interlock status. true means motors run, false motors don't run
|
||||
bool get_interlock() const { return _flags.interlock; };
|
||||
bool get_interlock() const { return _flags.interlock; }
|
||||
|
||||
// set_roll, set_pitch, set_yaw, set_throttle
|
||||
void set_roll(float roll_in) { _roll_in = roll_in; }; // range -1 ~ +1
|
||||
|
Loading…
Reference in New Issue
Block a user