diff --git a/libraries/AP_Motors/AP_Motors6DOF.h b/libraries/AP_Motors/AP_Motors6DOF.h index ff356e7f14..72a70409fc 100644 --- a/libraries/AP_Motors/AP_Motors6DOF.h +++ b/libraries/AP_Motors/AP_Motors6DOF.h @@ -29,7 +29,7 @@ public: SUB_FRAME_CUSTOM } sub_frame_t; - const char* get_frame_string() override { return _frame_class_string; }; + const char* get_frame_string() const override { return _frame_class_string; }; // Override parent void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override; diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index ba7b9fc0a3..d02e3bcd98 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -49,7 +49,7 @@ public: // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict uint16_t get_motor_mask() override; - const char* get_frame_string() override { return "COAX"; } + const char* get_frame_string() const override { return "COAX"; } protected: // output - sends commands to the motors diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index d73c69caee..9539d24969 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -159,7 +159,7 @@ public: // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; - const char* get_frame_string() override { return "HELI"; } + const char* get_frame_string() const override { return "HELI"; } protected: diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index fa11e67e73..1ca8cb2a7f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -99,7 +99,7 @@ public: // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; - const char* get_frame_string() override { return "HELI_DUAL"; } + const char* get_frame_string() const override { return "HELI_DUAL"; } protected: diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.h b/libraries/AP_Motors/AP_MotorsHeli_Quad.h index 5ee66672cd..50909453d0 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.h @@ -77,7 +77,7 @@ public: // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; - const char* get_frame_string() override { return "HELI_QUAD"; } + const char* get_frame_string() const override { return "HELI_QUAD"; } protected: diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index d9b729808b..122c8c8e88 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -42,7 +42,7 @@ void AP_MotorsMatrix::init(motor_frame_class frame_class, motor_frame_type frame // dedicated init for lua scripting bool AP_MotorsMatrix::init(uint8_t expected_num_motors) { - if (_last_frame_class != MOTOR_FRAME_SCRIPTING_MATRIX) { + if (_active_frame_class != MOTOR_FRAME_SCRIPTING_MATRIX) { // not the correct class return false; } diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index f1a8d9da00..ad69b7b38f 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -70,8 +70,9 @@ public: // using copter motors for forward flight float get_roll_factor(uint8_t i) override { return _roll_factor[i]; } - const char* get_frame_string() override { return _frame_class_string; } - const char* get_type_string() override { return _frame_type_string; } + const char* get_frame_string() const override { return _frame_class_string; } + const char* get_type_string() const override { return _frame_type_string; } + // disable the use of motor torque to control yaw. Used when an external mechanism such // as vectoring is used for yaw control void disable_yaw_torque(void) override; diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 5bdbe1006a..32317e9a10 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -49,7 +49,7 @@ public: // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict uint16_t get_motor_mask() override; - const char* get_frame_string() override { return "SINGLE"; } + const char* get_frame_string() const override { return "SINGLE"; } protected: // output - sends commands to the motors diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.h b/libraries/AP_Motors/AP_MotorsTailsitter.h index a2a26c508b..bf9f8a322d 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.h +++ b/libraries/AP_Motors/AP_MotorsTailsitter.h @@ -33,7 +33,7 @@ public: // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict uint16_t get_motor_mask() override; - const char* get_frame_string() override { return "TAILSITTER"; } + const char* get_frame_string() const override { return "TAILSITTER"; } protected: // calculate motor outputs diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 36bbb81d08..df3a0b895e 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -54,7 +54,7 @@ public: // using copter motors for forward flight float get_roll_factor(uint8_t i) override; - const char* get_frame_string() override { return "TRI"; } + const char* get_frame_string() const override { return "TRI"; } protected: // output - sends commands to the motors diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index b172192c70..990feaada9 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -49,7 +49,7 @@ public: }; // return string corresponding to frame_class - virtual const char* get_frame_string() = 0; + virtual const char* get_frame_string() const = 0; enum motor_frame_type { MOTOR_FRAME_TYPE_PLUS = 0, @@ -71,7 +71,7 @@ public: }; // return string corresponding to frame_type - virtual const char* get_type_string() { return ""; } + virtual const char* get_type_string() const { return ""; } // Constructor AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);