From f830ce5078766199c95ef29564d973713c2fbdf6 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 14 Jan 2018 15:16:27 -0800 Subject: [PATCH] Update to new ROI command --- libs/mavlink/include/mavlink/v2.0 | 2 +- src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc | 2 +- src/MissionManager/MavCmdInfoCommon.json | 46 +++++++++++++++++++++ src/comm/MockLink.cc | 8 +--- 4 files changed, 50 insertions(+), 8 deletions(-) diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index 5be9f5bf6..a31f7d989 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 5be9f5bf6002d58199cafafb5d416929fb8d8bcd +Subproject commit a31f7d989dffc2e554c26ad2c22c2a432a48fa74 diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 1a0b3ff28..3a5c7972e 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -290,7 +290,7 @@ QList PX4FirmwarePlugin::supportedMissionCommands(void) << MAV_CMD_DO_SET_SERVO << MAV_CMD_DO_CHANGE_SPEED << MAV_CMD_DO_LAND_START - << MAV_CMD_DO_SET_ROI + << MAV_CMD_DO_SET_ROI_LOCATION << MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET << MAV_CMD_DO_SET_ROI_NONE << MAV_CMD_DO_MOUNT_CONFIGURE << MAV_CMD_DO_MOUNT_CONTROL << MAV_CMD_SET_CAMERA_MODE diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 1995c7651..9a7dd6cbc 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -624,6 +624,52 @@ "default": 0 } }, + { + "id": 195, + "rawName": "MAV_CMD_DO_SET_ROI_LOCATION", + "friendlyName": "Region of interest (ROI)" , + "description": "Sets the region of interest for cameras.", + "specifiesCoordinate": true, + "standaloneCoordinate": true, + "friendlyEdit": true, + "category": "Camera" + }, + { + "id": 196, + "rawName": "MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET", + "friendlyName": "ROI to next waypoint" , + "description": "Sets the region of interest to point towards the next waypoint with optional offsets.", + "specifiesCoordinate": false, + "friendlyEdit": true, + "category": "Camera", + "param5": { + "label": "Pitch offset", + "default": 0, + "units": "deg", + "decimalPlaces": 0 + }, + "param6": { + "label": "Roll offset", + "default": 0, + "units": "deg", + "decimalPlaces": 0 + }, + "param7": { + "label": "Yaw offset", + "default": 0, + "units": "deg", + "decimalPlaces": 0 + } + }, + { + "id": 197, + "rawName": "MAV_CMD_DO_SET_ROI_NONE", + "friendlyName": "Cancel ROI" , + "description": "Cancels the region of interest.", + "specifiesCoordinate": false, + "friendlyEdit": true, + "category": "Camera" + }, { "id": 200, "rawName": "MAV_CMD_DO_CONTROL_VIDEO", "friendlyName": "Control video" }, { "id": 201, diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index e4e28dcc5..013e81e95 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -914,12 +914,8 @@ void MockLink::_respondWithAutopilotVersion(void) (uint8_t *)&customVersion, // os_custom_version, 0, // vendor_id, 0, // product_id, - 0 // uid -#if defined(NO_ARDUPILOT_DIALECT) - //-- Once the MAVLink module is updated, this should show up. In the mean time, it's disabled. - ,0 // uid2 -#endif - ); + 0, // uid + 0); // uid2 respondWithMavlinkMessage(msg); } -- 2.22.0