Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_MAVLink: use long-to-int conversion code for SET_ROI_SYSID #24361

Merged
merged 2 commits into from Aug 1, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
5 changes: 5 additions & 0 deletions Tools/autotest/arducopter.py
Expand Up @@ -5213,6 +5213,11 @@ def Mount(self):
)
self.test_mount_pitch(-89, 5, mavutil.mavlink.MAV_MOUNT_MODE_SYSID_TARGET, hold=2)

self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_NONE)
self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_SET_ROI_SYSID,
p1=self.mav.source_system,
)
self.mav.mav.global_position_int_send(
0, # time boot ms
int(roi_lat * 1e7),
Expand Down
17 changes: 3 additions & 14 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Expand Up @@ -4742,9 +4742,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
}
#endif

case MAV_CMD_DO_SET_ROI_SYSID:
return handle_command_do_set_roi_sysid(packet);

case MAV_CMD_DO_JUMP_TAG:
case MAV_CMD_DO_SET_MISSION_CURRENT:
result = handle_command_do_set_mission_current(packet);
Expand Down Expand Up @@ -5070,31 +5067,23 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_none()
mount->set_mode_to_default();
return MAV_RESULT_ACCEPTED;
}
#endif

MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_sysid(const uint8_t sysid)
{
#if HAL_MOUNT_ENABLED
AP_Mount *mount = AP::mount();
if (mount == nullptr) {
return MAV_RESULT_UNSUPPORTED;
}
mount->set_target_sysid(sysid);

return MAV_RESULT_ACCEPTED;
#else
return MAV_RESULT_UNSUPPORTED;
#endif
}

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);
}

MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_sysid(const mavlink_command_long_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)
{
Expand Down Expand Up @@ -5143,9 +5132,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
case MAV_CMD_DO_SET_ROI:
case MAV_CMD_DO_SET_ROI_LOCATION:
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);
#if HAL_MOUNT_ENABLED
case MAV_CMD_DO_SET_ROI_NONE:
return handle_command_do_set_roi_none();
#endif
Expand Down