AP_Mount: remove un-needed initialisations
These objects should always be created with new() or statically.
This commit is contained in:
parent
c5a69d8ec2
commit
57bc4d8736
@ -395,16 +395,9 @@ const AP_Param::GroupInfo AP_Mount::var_info[] = {
|
||||
|
||||
AP_Mount::AP_Mount(const AP_AHRS_TYPE &ahrs, const struct Location ¤t_loc) :
|
||||
_ahrs(ahrs),
|
||||
_current_loc(current_loc),
|
||||
_num_instances(0),
|
||||
_primary(0)
|
||||
_current_loc(current_loc)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
// initialise backend pointers and mode
|
||||
for (uint8_t i=0; i<AP_MOUNT_MAX_INSTANCES; i++) {
|
||||
_backends[i] = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
// init - detect and initialise all mounts
|
||||
|
@ -67,22 +67,7 @@ class AP_Mount_Alexmos : public AP_Mount_Backend
|
||||
public:
|
||||
//constructor
|
||||
AP_Mount_Alexmos(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance):
|
||||
AP_Mount_Backend(frontend, state, instance),
|
||||
_port(nullptr),
|
||||
_initialised(false),
|
||||
_board_version(0),
|
||||
_current_firmware_version(0.0f),
|
||||
_firmware_beta_version(0),
|
||||
_gimbal_3axis(false),
|
||||
_gimbal_bat_monitoring(false),
|
||||
_current_angle(0,0,0),
|
||||
_param_read_once(false),
|
||||
_checksum(0),
|
||||
_step(0),
|
||||
_command_id(0),
|
||||
_payload_length(0),
|
||||
_payload_counter(0),
|
||||
_last_command_confirmed(false)
|
||||
AP_Mount_Backend(frontend, state, instance)
|
||||
{}
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
|
@ -6,11 +6,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_Mount_SToRM32::AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
||||
AP_Mount_Backend(frontend, state, instance),
|
||||
_initialised(false),
|
||||
_sysid(0),
|
||||
_compid(0),
|
||||
_chan(MAVLINK_COMM_0),
|
||||
_last_send(0)
|
||||
_chan(MAVLINK_COMM_0)
|
||||
{}
|
||||
|
||||
// update mount position - should be called periodically
|
||||
|
@ -8,11 +8,6 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
||||
AP_Mount_Backend(frontend, state, instance),
|
||||
_port(nullptr),
|
||||
_initialised(false),
|
||||
_last_send(0),
|
||||
_reply_length(0),
|
||||
_reply_counter(0),
|
||||
_reply_type(ReplyType_UNKNOWN)
|
||||
{}
|
||||
|
||||
|
@ -20,13 +20,8 @@ public:
|
||||
_roll_idx(SRV_Channel::k_none),
|
||||
_tilt_idx(SRV_Channel::k_none),
|
||||
_pan_idx(SRV_Channel::k_none),
|
||||
_open_idx(SRV_Channel::k_none),
|
||||
_last_check_servo_map_ms(0)
|
||||
_open_idx(SRV_Channel::k_none)
|
||||
{
|
||||
// init to no axis being controlled
|
||||
_flags.roll_control = false;
|
||||
_flags.tilt_control = false;
|
||||
_flags.pan_control = false;
|
||||
}
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
|
@ -12,7 +12,6 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
||||
AP_Mount_Backend(frontend, state, instance),
|
||||
_initialised(false),
|
||||
_gimbal(frontend._ahrs)
|
||||
{}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user