mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: make frame*string getters more const
This commit is contained in:
parent
236961f17f
commit
9bc8a8c912
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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:
|
||||
|
||||
|
|
|
@ -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:
|
||||
|
||||
|
|
|
@ -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:
|
||||
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue