ArduCopter: use enum class for mount type

This commit is contained in:
Peter Barker 2023-05-24 17:07:42 +10:00 committed by Randy Mackay
parent 3acc917ea7
commit 078debb893
2 changed files with 3 additions and 3 deletions

View File

@ -767,7 +767,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t
switch (packet.command) { switch (packet.command) {
case MAV_CMD_DO_MOUNT_CONTROL: case MAV_CMD_DO_MOUNT_CONTROL:
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead // if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) && if ((copter.camera_mount.get_mount_type() != AP_Mount::Type::None) &&
!copter.camera_mount.has_pan_control()) { !copter.camera_mount.has_pan_control()) {
copter.flightmode->auto_yaw.set_yaw_angle_rate((float)packet.param3, 0.0f); copter.flightmode->auto_yaw.set_yaw_angle_rate((float)packet.param3, 0.0f);
} }
@ -1069,7 +1069,7 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
switch (msg.msgid) { switch (msg.msgid) {
case MAVLINK_MSG_ID_MOUNT_CONTROL: case MAVLINK_MSG_ID_MOUNT_CONTROL:
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead // if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) && if ((copter.camera_mount.get_mount_type() != AP_Mount::Type::None) &&
!copter.camera_mount.has_pan_control()) { !copter.camera_mount.has_pan_control()) {
copter.flightmode->auto_yaw.set_yaw_angle_rate( copter.flightmode->auto_yaw.set_yaw_angle_rate(
mavlink_msg_mount_control_get_input_c(&msg) * 0.01f, mavlink_msg_mount_control_get_input_c(&msg) * 0.01f,

View File

@ -1892,7 +1892,7 @@ void ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd)
{ {
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead // if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) && if ((copter.camera_mount.get_mount_type() != AP_Mount::Type::None) &&
!copter.camera_mount.has_pan_control()) { !copter.camera_mount.has_pan_control()) {
auto_yaw.set_yaw_angle_rate(cmd.content.mount_control.yaw,0.0f); auto_yaw.set_yaw_angle_rate(cmd.content.mount_control.yaw,0.0f);
} }