diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 1d2288b0daab0..7cbec7f6756d6 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -499,6 +499,18 @@ void AP_Mount::handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_ } } +MAV_RESULT AP_Mount::handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet) +{ + set_target_sysid((uint8_t)packet.param1); + return MAV_RESULT_ACCEPTED; +} + +MAV_RESULT AP_Mount::handle_command_do_set_roi_none() +{ + set_mode_to_default(); + return MAV_RESULT_ACCEPTED; +} + MAV_RESULT AP_Mount::handle_command(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { @@ -510,6 +522,10 @@ MAV_RESULT AP_Mount::handle_command(const mavlink_command_int_t &packet, const m return handle_command_do_gimbal_manager_pitchyaw(packet); case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE: return handle_command_do_gimbal_manager_configure(packet, msg); + case MAV_CMD_DO_SET_ROI_SYSID: + return handle_command_do_set_roi_sysid(packet); + case MAV_CMD_DO_SET_ROI_NONE: + return handle_command_do_set_roi_none(); default: return MAV_RESULT_UNSUPPORTED; } diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 7030695728783..462df7bac5183 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -177,6 +177,12 @@ class AP_Mount void set_target_sysid(uint8_t sysid) { set_target_sysid(_primary, sysid); } void set_target_sysid(uint8_t instance, uint8_t sysid); + // handling of set_roi_sysid message + MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet); + + // handling of set_roi_none message + MAV_RESULT handle_command_do_set_roi_none(); + // mavlink message handling: MAV_RESULT handle_command(const mavlink_command_int_t &packet, const mavlink_message_t &msg); void handle_param_value(const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 04865cc574d89..1640954d7c949 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -639,10 +639,6 @@ class GCS_MAVLINK MAV_RESULT handle_command_battery_reset(const mavlink_command_long_t &packet); void handle_command_long(const mavlink_message_t &msg); MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_set_roi_sysid(const uint8_t sysid); - MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet); - MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_set_roi_none(); #if HAL_MOUNT_ENABLED virtual MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 7d9f38f5b8207..c54c051c0d4d5 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5070,34 +5070,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_external_position_estimate(const mavl } #endif // AP_AHRS_POSITION_RESET_ENABLED -#if HAL_MOUNT_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_none() -{ - AP_Mount *mount = AP::mount(); - if (mount == nullptr) { - return MAV_RESULT_UNSUPPORTED; - } - mount->set_mode_to_default(); - return MAV_RESULT_ACCEPTED; -} - -MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_sysid(const uint8_t sysid) -{ - AP_Mount *mount = AP::mount(); - if (mount == nullptr) { - return MAV_RESULT_UNSUPPORTED; - } - mount->set_target_sysid(sysid); - - return MAV_RESULT_ACCEPTED; -} - -MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet) -{ - return handle_command_do_set_roi_sysid((uint8_t)packet.param1); -} -#endif - MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const mavlink_command_int_t &packet) { // be aware that this method is called for both MAV_CMD_DO_SET_ROI @@ -5147,9 +5119,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_command_do_set_roi(packet); #if HAL_MOUNT_ENABLED case MAV_CMD_DO_SET_ROI_SYSID: - return handle_command_do_set_roi_sysid(packet); case MAV_CMD_DO_SET_ROI_NONE: - return handle_command_do_set_roi_none(); case MAV_CMD_DO_MOUNT_CONFIGURE: case MAV_CMD_DO_MOUNT_CONTROL: case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: