mavlink_mission: remove support for DO_SET_CAMERA_ZOOM

Camera controls should not happen through the flight controller, and
the control allocation has no means of controlling the camera zoom.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer 2023-03-07 10:18:51 +01:00 committed by Beat Küng
parent 27658354da
commit 1218d9b2fc
3 changed files with 0 additions and 28 deletions

View File

@ -118,11 +118,6 @@ 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 PARACHUTE_ACTION_DISABLE = 0
uint8 PARACHUTE_ACTION_ENABLE = 1
uint8 PARACHUTE_ACTION_RELEASE = 2

View File

@ -1545,7 +1545,6 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
case MAV_CMD_OBLIQUE_SURVEY:
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:

View File

@ -525,28 +525,6 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
vehicle_command.param2, vehicle_command.param3, vehicle_command.param4,
vehicle_command.param5, vehicle_command.param6, vehicle_command.param7);
} 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 if (cmd_mavlink.command == MAV_CMD_INJECT_FAILURE) {
if (_mavlink->failure_injection_enabled()) {
_cmd_pub.publish(vehicle_command);