mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLink: move handling of all do-set-roi to AP_Mount library
This commit is contained in:
parent
3927521aa6
commit
e3f0904616
@ -639,10 +639,6 @@ protected:
|
||||
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);
|
||||
|
@ -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:
|
||||
|
Loading…
Reference in New Issue
Block a user