GCS_MAVLink: accept mount commands as command_int

This commit is contained in:
Peter Barker 2023-08-17 17:19:03 +10:00 committed by Peter Barker
parent 02d1eca49b
commit a2d5244b10
2 changed files with 10 additions and 15 deletions

View File

@ -645,7 +645,7 @@ protected:
MAV_RESULT handle_command_do_set_roi_none();
#if HAL_MOUNT_ENABLED
virtual MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
virtual MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
#endif
MAV_RESULT handle_command_mag_cal(const mavlink_command_int_t &packet);

View File

@ -4626,15 +4626,15 @@ MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_comman
#endif // HAL_INS_ACCELCAL_ENABLED
#if HAL_MOUNT_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
AP_Mount *mount = AP::mount();
if (mount == nullptr) {
return MAV_RESULT_UNSUPPORTED;
}
return mount->handle_command_long(packet, msg);
return mount->handle_command(packet, msg);
}
#endif
#endif // HAL_MOUNT_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_command_int_t &packet)
{
@ -4870,16 +4870,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
result = handle_command_preflight_calibration(packet, msg);
break;
#if HAL_MOUNT_ENABLED
case MAV_CMD_DO_MOUNT_CONFIGURE:
case MAV_CMD_DO_MOUNT_CONTROL:
case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE:
// some mount commands require the source sysid and compid
result = handle_command_mount(packet, msg);
break;
#endif
default:
result = try_command_long_as_command_int(packet, msg);
break;
@ -5160,7 +5150,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
return handle_command_do_set_roi_sysid(packet);
case MAV_CMD_DO_SET_ROI_NONE:
return handle_command_do_set_roi_none();
#endif
case MAV_CMD_DO_MOUNT_CONFIGURE:
case MAV_CMD_DO_MOUNT_CONTROL:
case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE:
return handle_command_mount(packet, msg);
#endif // HAL_MOUNT_ENABLED
case MAV_CMD_DO_SET_HOME:
return handle_command_do_set_home(packet);
#if AP_AHRS_POSITION_RESET_ENABLED