diff --git a/msg/actuator_controls.msg b/msg/actuator_controls.msg index d266f25bea..a45d0e0b3c 100644 --- a/msg/actuator_controls.msg +++ b/msg/actuator_controls.msg @@ -9,8 +9,16 @@ uint8 INDEX_FLAPS = 4 uint8 INDEX_SPOILERS = 5 uint8 INDEX_AIRBRAKES = 6 uint8 INDEX_LANDING_GEAR = 7 + +uint8 INDEX_GIMBAL_SHUTTER = 3 +uint8 INDEX_CAMERA_ZOOM = 4 + uint8 GROUP_INDEX_ATTITUDE = 0 uint8 GROUP_INDEX_ATTITUDE_ALTERNATE = 1 +uint8 GROUP_INDEX_GIMBAL = 2 +uint8 GROUP_INDEX_MANUAL_PASSTHROUGH = 3 +uint8 GROUP_INDEX_PAYLOAD = 6 + uint64 timestamp_sample # the timestamp the data this control response is based on was sampled float32[8] control diff --git a/msg/vehicle_command.msg b/msg/vehicle_command.msg index 8c4d41cedd..a2f8d53f73 100644 --- a/msg/vehicle_command.msg +++ b/msg/vehicle_command.msg @@ -68,6 +68,7 @@ uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm| uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.) +uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization @@ -100,6 +101,11 @@ uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location uint8 VEHICLE_ROI_TARGET = 4 # Point toward target uint8 VEHICLE_ROI_ENUM_END = 5 +uint8 VEHICLE_CAMERA_ZOOM_TYPE_STEP = 0 # Zoom one step increment +uint8 VEHICLE_CAMERA_ZOOM_TYPE_CONTINUOUS = 1 # Continuous zoom up/down until stopped +uint8 VEHICLE_CAMERA_ZOOM_TYPE_RANGE = 2 # Zoom value as proportion of full camera range +uint8 VEHICLE_CAMERA_ZOOM_TYPE_FOCAL_LENGTH = 3 # Zoom to a focal length + uint8 ORB_QUEUE_LENGTH = 3 float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 662d8e4e92..ec0a183fe6 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -1058,6 +1058,7 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_ case vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST: case vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL: case vehicle_command_s::VEHICLE_CMD_SET_CAMERA_MODE: + case vehicle_command_s::VEHICLE_CMD_SET_CAMERA_ZOOM: case vehicle_command_s::VEHICLE_CMD_DO_CHANGE_SPEED: case vehicle_command_s::VEHICLE_CMD_DO_LAND_START: case vehicle_command_s::VEHICLE_CMD_DO_GO_AROUND: diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 14b1b4f69f..dfc3ac0046 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -1476,6 +1476,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * case MAV_CMD_DO_SET_CAM_TRIGG_DIST: case MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL: case MAV_CMD_SET_CAMERA_MODE: + case MAV_CMD_SET_CAMERA_ZOOM: case MAV_CMD_DO_VTOL_TRANSITION: case MAV_CMD_NAV_DELAY: case MAV_CMD_NAV_RETURN_TO_LAUNCH: @@ -1551,6 +1552,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * case NAV_CMD_DO_SET_CAM_TRIGG_DIST: case NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL: case NAV_CMD_SET_CAMERA_MODE: + case NAV_CMD_SET_CAMERA_ZOOM: case NAV_CMD_DO_VTOL_TRANSITION: break; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 62ffd47404..fcb7adae79 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -521,6 +521,27 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED; } + } else if (cmd_mavlink.command == MAV_CMD_SET_CAMERA_ZOOM) { + struct actuator_controls_s actuator_controls = {}; + actuator_controls.timestamp = hrt_absolute_time(); + + for (size_t i = 0; i < 8; i++) { + actuator_controls.control[i] = NAN; + } + + switch ((int)(cmd_mavlink.param1 + 0.5f)) { + case vehicle_command_s::VEHICLE_CAMERA_ZOOM_TYPE_RANGE: + actuator_controls.control[actuator_controls_s::INDEX_CAMERA_ZOOM] = cmd_mavlink.param2 / 50.0f - 1.0f; + break; + case vehicle_command_s::VEHICLE_CAMERA_ZOOM_TYPE_STEP: + case vehicle_command_s::VEHICLE_CAMERA_ZOOM_TYPE_CONTINUOUS: + case vehicle_command_s::VEHICLE_CAMERA_ZOOM_TYPE_FOCAL_LENGTH: + default: + send_ack = false; + } + + _actuator_controls_pubs[actuator_controls_s::GROUP_INDEX_GIMBAL].publish(actuator_controls); + } else { send_ack = false; diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index 09c0027520..0364b14320 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -102,6 +102,7 @@ MissionBlock::is_mission_item_reached() case NAV_CMD_DO_SET_CAM_TRIGG_DIST: case NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL: case NAV_CMD_SET_CAMERA_MODE: + case NAV_CMD_SET_CAMERA_ZOOM: return true; case NAV_CMD_DO_VTOL_TRANSITION: diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index 0b07c32fc5..8f8a670455 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -268,6 +268,7 @@ MissionFeasibilityChecker::checkMissionItemValidity(const mission_s &mission) missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_DIST && missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL && missionitem.nav_cmd != NAV_CMD_SET_CAMERA_MODE && + missionitem.nav_cmd != NAV_CMD_SET_CAMERA_ZOOM && missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION) { mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: item %i: unsupported cmd: %d", (int)(i + 1), @@ -392,6 +393,7 @@ MissionFeasibilityChecker::checkTakeoff(const mission_s &mission, float home_alt missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_DIST && missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL && missionitem.nav_cmd != NAV_CMD_SET_CAMERA_MODE && + missionitem.nav_cmd != NAV_CMD_SET_CAMERA_ZOOM && missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION); } } diff --git a/src/modules/navigator/navigation.h b/src/modules/navigator/navigation.h index 882cf1cb4e..1c06f52c41 100644 --- a/src/modules/navigator/navigation.h +++ b/src/modules/navigator/navigation.h @@ -83,6 +83,7 @@ enum NAV_CMD { NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214, NAV_CMD_DO_SET_CAM_TRIGG_DIST = 206, NAV_CMD_SET_CAMERA_MODE = 530, + NAV_CMD_SET_CAMERA_ZOOM = 531, NAV_CMD_IMAGE_START_CAPTURE = 2000, NAV_CMD_IMAGE_STOP_CAPTURE = 2001, NAV_CMD_DO_TRIGGER_CONTROL = 2003,