diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index f372acafee..e9216662db 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -331,7 +331,7 @@ void AP_MotorsHeli::output_test() } // allow_arming - returns true if main rotor is spinning and it is ok to arm -bool AP_MotorsHeli::allow_arming() +bool AP_MotorsHeli::allow_arming() const { // ensure main rotor has started if (_rsc_mode != AP_MOTORS_HELI_RSC_MODE_NONE && _servo_rsc->control_in > 0) { @@ -349,7 +349,7 @@ void AP_MotorsHeli::set_desired_rotor_speed(int16_t desired_speed) } // return true if the main rotor is up to speed -bool AP_MotorsHeli::motor_runup_complete() +bool AP_MotorsHeli::motor_runup_complete() const { // if we have no control of motors, assume pilot has spun them up if (_rsc_mode == AP_MOTORS_HELI_RSC_MODE_NONE) { diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 1f89d81a28..682a6254b8 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -146,44 +146,44 @@ public: // // allow_arming - returns true if main rotor is spinning and it is ok to arm - bool allow_arming(); + bool allow_arming() const; // _tail_type - returns the tail type (servo, servo with ext gyro, direct drive var pitch, direct drive fixed pitch) - int16_t tail_type() { return _tail_type; } + int16_t tail_type() const { return _tail_type; } // ext_gyro_gain - gets and sets external gyro gain as a pwm (1000~2000) - int16_t ext_gyro_gain() { return _ext_gyro_gain; } + int16_t ext_gyro_gain() const { return _ext_gyro_gain; } void ext_gyro_gain(int16_t pwm) { _ext_gyro_gain = pwm; } // has_flybar - returns true if we have a mechical flybar - bool has_flybar() { return _flybar_mode; } + bool has_flybar() const { return _flybar_mode; } // get_collective_mid - returns collective mid position as a number from 0 ~ 1000 - int16_t get_collective_mid() { return _collective_mid; } + int16_t get_collective_mid() const { return _collective_mid; } // get_collective_out - returns collective position from last output as a number from 0 ~ 1000 - int16_t get_collective_out() { return _collective_out; } + int16_t get_collective_out() const { return _collective_out; } // set_collective_for_landing - limits collective from going too low if we know we are landed void set_collective_for_landing(bool landing) { _heliflags.landing_collective = landing; } // get_rsc_mode - gets the rotor speed control method (AP_MOTORS_HELI_RSC_MODE_NONE, AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH or AP_MOTORS_HELI_RSC_MODE_SETPOINT) - uint8_t get_rsc_mode() { return _rsc_mode; } + uint8_t get_rsc_mode() const { return _rsc_mode; } // get_rsc_setpoint - gets contents of _rsc_setpoint parameter (0~1000) - int16_t get_rsc_setpoint() { return _rsc_setpoint; } + int16_t get_rsc_setpoint() const { return _rsc_setpoint; } // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000 void set_desired_rotor_speed(int16_t desired_speed); // return true if the main rotor is up to speed - bool motor_runup_complete(); + bool motor_runup_complete() const; // recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters void recalc_scalers(); // get_phase_angle - returns phase angle - int16_t get_phase_angle() { return _phase_angle; } + int16_t get_phase_angle() const { return _phase_angle; } // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[];