Commit 644f6c83 authored by Gus Grubba's avatar Gus Grubba

Updating MAVLink camera/video commands.

parent 78115454
Subproject commit 2faa6d49834aa203e2a3eeeeed588728fb14c431 Subproject commit 6bbc8a51d8f37537732d3f5170093d49e64c6f4b
This diff is collapsed.
...@@ -47,7 +47,7 @@ void CameraSectionTest::init(void) ...@@ -47,7 +47,7 @@ void CameraSectionTest::init(void)
MissionItem(0, MAV_CMD_DO_MOUNT_CONTROL, MAV_FRAME_MISSION, 10.1234, 0, 20.1234, 0, 0, 0, MAV_MOUNT_MODE_MAVLINK_TARGETING, true, false), MissionItem(0, MAV_CMD_DO_MOUNT_CONTROL, MAV_FRAME_MISSION, 10.1234, 0, 20.1234, 0, 0, 0, MAV_MOUNT_MODE_MAVLINK_TARGETING, true, false),
this); this);
_validTimeItem = new SimpleMissionItem(_offlineVehicle, _validTimeItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, -1, -1, 0, 0, true, false), MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, NAN, NAN, NAN, NAN, true, false),
this); this);
_validDistanceItem = new SimpleMissionItem(_offlineVehicle, _validDistanceItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 72, 0, 0, 0, 0, 0, 0, true, false), MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 72, 0, 0, 0, 0, 0, 0, true, false),
...@@ -57,22 +57,19 @@ void CameraSectionTest::init(void) ...@@ -57,22 +57,19 @@ void CameraSectionTest::init(void)
MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // camera id = 0, all cameras 0, // camera id = 0, all cameras
-1, // -1 Max FPS 0, // No CAMERA_CAPTURE_STATUS streaming
-1, // Max horizontal resolution NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
-1, // Max vertical resolution
0, // Np CAMERA_CAPTURE_STATUS streaming
0, 0, // param 6-7 not used
true, // autocontinue true, // autocontinue
false), // isCurrentItem false), // isCurrentItem
this); this);
_validStopVideoItem = new SimpleMissionItem(_offlineVehicle, _validStopVideoItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, MAV_CMD_VIDEO_STOP_CAPTURE, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false), MissionItem(0, MAV_CMD_VIDEO_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false),
this); this);
_validStopDistanceItem = new SimpleMissionItem(_offlineVehicle, _validStopDistanceItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false), MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false),
this); this);
_validStopTimeItem = new SimpleMissionItem(_offlineVehicle, _validStopTimeItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false), MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false),
this); this);
_validCameraPhotoModeItem = new SimpleMissionItem(_offlineVehicle, _validCameraPhotoModeItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, // sequence number MissionItem(0, // sequence number
...@@ -80,7 +77,8 @@ void CameraSectionTest::init(void) ...@@ -80,7 +77,8 @@ void CameraSectionTest::init(void)
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // camera id = 0, all cameras 0, // camera id = 0, all cameras
CameraSection::CameraModePhoto, CameraSection::CameraModePhoto,
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused NAN, // Audio off/on
NAN, NAN, NAN, NAN, // param 4-7 reserved
true, // autocontinue true, // autocontinue
false), // isCurrentItem false), // isCurrentItem
this); this);
...@@ -90,7 +88,8 @@ void CameraSectionTest::init(void) ...@@ -90,7 +88,8 @@ void CameraSectionTest::init(void)
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // camera id = 0, all cameras 0, // camera id = 0, all cameras
CameraSection::CameraModeVideo, CameraSection::CameraModeVideo,
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused NAN, // Audio off/on
NAN, NAN, NAN, NAN, // param 4-7 reserved
true, // autocontinue true, // autocontinue
false), // isCurrentItem false), // isCurrentItem
this); this);
...@@ -98,12 +97,10 @@ void CameraSectionTest::init(void) ...@@ -98,12 +97,10 @@ void CameraSectionTest::init(void)
MissionItem(0, MissionItem(0,
MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // camera id = 0, all cameras 0, // camera id = 0, all cameras
0, // Interval (none) 0, // Interval (none)
1, // Take 1 photo 1, // Take 1 photo
-1, // Max horizontal resolution NAN, NAN, NAN, NAN, // param 4-7 not reserved
-1, // Max vertical resolution
0, 0, // param 6-7 not used
true, // autoContinue true, // autoContinue
false), // isCurrentItem false), // isCurrentItem
this); this);
...@@ -703,8 +700,6 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) ...@@ -703,8 +700,6 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Duration between two consecutive pictures (in seconds) Mission Param #2 Duration between two consecutive pictures (in seconds)
Mission Param #3 Number of images to capture total - 0 for unlimited capture Mission Param #3 Number of images to capture total - 0 for unlimited capture
Mission Param #4 Resolution horizontal in pixels (set to -1 for highest resolution possible)
Mission Param #5 Resolution vertical in pixels (set to -1 for highest resolution possible)
*/ */
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, this); SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, this);
...@@ -862,10 +857,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) ...@@ -862,10 +857,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
/* /*
MAV_CMD_VIDEO_START_CAPTURE WIP: Starts video capture (recording) MAV_CMD_VIDEO_START_CAPTURE WIP: Starts video capture (recording)
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Frames per second, set to -1 for highest framerate possible. Mission Param #2 Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise time in Hz)
Mission Param #3 Resolution horizontal in pixels (set to -1 for highest resolution possible)
Mission Param #4 Resolution vertical in pixels (set to -1 for highest resolution possible)
Mission Param #5 Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise time in Hz)
*/ */
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, this); SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, this);
...@@ -1069,8 +1061,6 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) ...@@ -1069,8 +1061,6 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Duration between two consecutive pictures (in seconds) Mission Param #2 Duration between two consecutive pictures (in seconds)
Mission Param #3 Number of images to capture total - 0 for unlimited capture Mission Param #3 Number of images to capture total - 0 for unlimited capture
Mission Param #4 Resolution horizontal in pixels (set to -1 for highest resolution possible)
Mission Param #5 Resolution vertical in pixels (set to -1 for highest resolution possible)
*/ */
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, this); SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, this);
......
...@@ -998,24 +998,19 @@ ...@@ -998,24 +998,19 @@
"description": "Start taking one or more photos.", "description": "Start taking one or more photos.",
"category": "Camera", "category": "Camera",
"param1": { "param1": {
"label": "Interval", "label": "Camera id",
"default": 0, "default": 0,
"units": "secs",
"decimalPlaces": 0 "decimalPlaces": 0
}, },
"param2": { "param2": {
"label": "Photo count", "label": "Interval",
"default": 1, "default": 0,
"units": "secs",
"decimalPlaces": 0 "decimalPlaces": 0
}, },
"param3": { "param3": {
"label": "Resolution", "label": "Photo count",
"default": -1, "default": 1,
"decimalPlaces": 0
},
"param6": {
"label": "Camera id",
"default": 0,
"decimalPlaces": 0 "decimalPlaces": 0
} }
}, },
...@@ -1042,16 +1037,6 @@ ...@@ -1042,16 +1037,6 @@
"label": "Camera id", "label": "Camera id",
"default": 0, "default": 0,
"decimalPlaces": 0 "decimalPlaces": 0
},
"param2": {
"label": "FPS",
"default": -1,
"decimalPlaces": 0
},
"param3": {
"label": "Resolution",
"default": -1,
"decimalPlaces": 0
} }
}, },
{ {
......
...@@ -1053,9 +1053,9 @@ void MissionManager::generateResumeMission(int resumeIndex) ...@@ -1053,9 +1053,9 @@ void MissionManager::generateResumeMission(int resumeIndex)
case MAV_CMD_IMAGE_START_CAPTURE: case MAV_CMD_IMAGE_START_CAPTURE:
{ {
// FIXME: Handle single image capture // FIXME: Handle single image capture
int cameraId = resumeItem->param6(); int cameraId = resumeItem->param1();
if (resumeItem->param1() == 0) { if (resumeItem->param3() == 1) {
// This is an individual image capture command, remove it // This is an individual image capture command, remove it
resumeMission.removeAt(resumeIndex); resumeMission.removeAt(resumeIndex);
break; break;
...@@ -1084,7 +1084,7 @@ void MissionManager::generateResumeMission(int resumeIndex) ...@@ -1084,7 +1084,7 @@ void MissionManager::generateResumeMission(int resumeIndex)
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
{ {
int cameraId = resumeItem->param1(); int cameraId = resumeItem->param1();
// If we already found an video stop, then all video start/stop commands are useless // If we've already found a video stop, then all video start/stop commands are useless
// De-dup repeated video start commands // De-dup repeated video start commands
// Otherwise keep only the last video start // Otherwise keep only the last video start
if (videoStopCameraIds.contains(cameraId) || videoStopCameraIds.contains(cameraId)) { if (videoStopCameraIds.contains(cameraId) || videoStopCameraIds.contains(cameraId)) {
......
...@@ -1146,9 +1146,7 @@ int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int ...@@ -1146,9 +1146,7 @@ int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int
0, // Camera ID, all cameras 0, // Camera ID, all cameras
0, // Interval (none) 0, // Interval (none)
1, // Take 1 photo 1, // Take 1 photo
-1, // Max horizontal resolution NAN, NAN, NAN, NAN, // param 4-7 reserved
-1, // Max vertical resolution
0, 0, // param 6-7 not used
true, // autoContinue true, // autoContinue
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
......
...@@ -90,11 +90,11 @@ public: ...@@ -90,11 +90,11 @@ public:
MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */
MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */
MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence */
MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */ MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence */
MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */
MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture */
MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */ MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture */
MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */
MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */
MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */
......
...@@ -924,7 +924,8 @@ void MockLink::_sendHomePosition(void) ...@@ -924,7 +924,8 @@ void MockLink::_sendHomePosition(void)
(int32_t)(_vehicleAltitude * 1000), (int32_t)(_vehicleAltitude * 1000),
0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f,
&bogus[0], &bogus[0],
0.0f, 0.0f, 0.0f); 0.0f, 0.0f, 0.0f,
0);
respondWithMavlinkMessage(msg); respondWithMavlinkMessage(msg);
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment