GCS_MAVLink: handle camera messages as COMMAND_INT as well as COMMAND_LONG

This commit is contained in:
Peter Barker 2023-10-31 13:30:01 +11:00 committed by Peter Barker
parent 685bdd3d3d
commit 187ae07225
2 changed files with 20 additions and 19 deletions

View File

@ -654,7 +654,7 @@ protected:
virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const; virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const;
MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg); MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet); MAV_RESULT handle_command_camera(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet);
virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc); virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc);
MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);

View File

@ -3449,14 +3449,14 @@ void GCS_MAVLINK::handle_system_time_message(const mavlink_message_t &msg)
#endif #endif
#if AP_CAMERA_ENABLED #if AP_CAMERA_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet) MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_int_t &packet)
{ {
AP_Camera *camera = AP::camera(); AP_Camera *camera = AP::camera();
if (camera == nullptr) { if (camera == nullptr) {
return MAV_RESULT_UNSUPPORTED; return MAV_RESULT_UNSUPPORTED;
} }
return camera->handle_command_long(packet); return camera->handle_command(packet);
} }
#endif #endif
@ -4725,22 +4725,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
switch (packet.command) { switch (packet.command) {
#if AP_CAMERA_ENABLED
case MAV_CMD_DO_DIGICAM_CONFIGURE:
case MAV_CMD_DO_DIGICAM_CONTROL:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_SET_CAMERA_ZOOM:
case MAV_CMD_SET_CAMERA_FOCUS:
case MAV_CMD_IMAGE_START_CAPTURE:
case MAV_CMD_IMAGE_STOP_CAPTURE:
case MAV_CMD_CAMERA_TRACK_POINT:
case MAV_CMD_CAMERA_TRACK_RECTANGLE:
case MAV_CMD_CAMERA_STOP_TRACKING:
case MAV_CMD_VIDEO_START_CAPTURE:
case MAV_CMD_VIDEO_STOP_CAPTURE:
result = handle_command_camera(packet);
break;
#endif
#if AP_GRIPPER_ENABLED #if AP_GRIPPER_ENABLED
case MAV_CMD_DO_GRIPPER: case MAV_CMD_DO_GRIPPER:
result = handle_command_do_gripper(packet); result = handle_command_do_gripper(packet);
@ -5037,6 +5021,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_storage_format(const mavlink_command_int_
MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{ {
switch (packet.command) { switch (packet.command) {
#if HAL_INS_ACCELCAL_ENABLED #if HAL_INS_ACCELCAL_ENABLED
case MAV_CMD_ACCELCAL_VEHICLE_POS: case MAV_CMD_ACCELCAL_VEHICLE_POS:
return handle_command_accelcal_vehicle_pos(packet); return handle_command_accelcal_vehicle_pos(packet);
@ -5073,6 +5058,22 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
case MAV_CMD_DO_SET_MODE: case MAV_CMD_DO_SET_MODE:
return handle_command_do_set_mode(packet); return handle_command_do_set_mode(packet);
#if AP_CAMERA_ENABLED
case MAV_CMD_DO_DIGICAM_CONFIGURE:
case MAV_CMD_DO_DIGICAM_CONTROL:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_SET_CAMERA_ZOOM:
case MAV_CMD_SET_CAMERA_FOCUS:
case MAV_CMD_IMAGE_START_CAPTURE:
case MAV_CMD_IMAGE_STOP_CAPTURE:
case MAV_CMD_CAMERA_TRACK_POINT:
case MAV_CMD_CAMERA_TRACK_RECTANGLE:
case MAV_CMD_CAMERA_STOP_TRACKING:
case MAV_CMD_VIDEO_START_CAPTURE:
case MAV_CMD_VIDEO_STOP_CAPTURE:
return handle_command_camera(packet);
#endif
case MAV_CMD_DO_SET_ROI_NONE: { case MAV_CMD_DO_SET_ROI_NONE: {
const Location zero_loc = Location(); const Location zero_loc = Location();
return handle_command_do_set_roi(zero_loc); return handle_command_do_set_roi(zero_loc);