Messages¶
GroundSdk FlightPlan Commands (MAVLink Commands)¶
Commands to be executed by the MAV. One set of commands forms a mission script. Some commands are tagged differs from MAVlink, which means their set of parameters is different from MAVlink one (https://mavlink.io/en/messages/common.html). If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y: Param 6, Z: Param 7. Each parameters is typed in float.
MAV_CMD_CONDITION_DELAY (Message code: 112)¶
Delay mission state machine.
Param: Label | Values | Units | Description |
---|---|---|---|
1: Delay | min: 0 | s | Delay |
2: | Not used | ||
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_DO_CHANGE_SPEED (Message code: 178)¶
Change speed and/or throttle set points.
differs from MAVlink
Param: Label | Values | Units | Description |
---|---|---|---|
1: Speed Type | 1 | Speed type (1=Ground Speed) | |
2: Speed | min: 1 max: 10 | m/s | Speed (-1 indicates no change) |
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_DO_SET_ROI (Message code: 201)¶
Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.
differs from MAVlink deprecated by MAVlink
Param: Label | Values | Units | Description |
---|---|---|---|
1: ROI Mode | 3 | Region of interest mode (MAV_ROI_LOCATION = 3) | |
2: | Not used | ||
3: | Not used | ||
4: | Not used | ||
5: Latitude | deg | Latitude coordinate | |
6: Longitude | deg | Longitude coordinate | |
7: Altitude | m | Altitude coordinate |
MAV_CMD_DO_MOUNT_CONTROL (Message code: 205)¶
Mission command to control a camera mount.
differs from MAVlink
Param: Label | Values | Units | Description |
---|---|---|---|
1: Tilt | min: -90 max: 90 | deg | Camera tilt angle |
2: | Not used | ||
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: Mode | 2 | Mount mode (MAV_MOUNT_MODE_MAVLINK_TARGETING = 2) |
MAV_CMD_VIDEO_START_CAPTURE (Message code: 2500)¶
Starts video capture (recording).
differs from MAVlink
Param: Label | Values | Units | Description |
---|---|---|---|
1: | Not used | ||
2: | Not used | ||
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_VIDEO_STOP_CAPTURE (Message code: 2501)¶
Stop the current video capture (recording).
differs from MAVlink
Param: Label | Values | Units | Description |
---|---|---|---|
1: | Not used | ||
2: | Not used | ||
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_PANORAMA_CREATE (Message code: 2800)¶
Create a panorama at the current position.
Param: Label | Values | Units | Description |
---|---|---|---|
1: Horizontal Angle | deg | Viewing angle horizontal of panorama | |
2: Vertical Angle | deg | Viewing angle vertical of panorama | |
3: Horizontal Speed | deg/s | Speed of the horizontal rotation | |
4: Vertical Speed | deg/s | Speed of the vertical rotation | |
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_IMAGE_START_CAPTURE (Message code: 2000)¶
Start image capture sequence. Sends ARSDK_CAMERA_PHOTO_RESULT_PHOTO_TAKEN after each capture. Capture mode should have been defined before by MAV_CMD_SET_STILL_CAPTURE_MODE.
differs from MAVlink
Param: Label | Values | Units | Description |
---|---|---|---|
1: Interval | min: 0 | s | Desired elapsed time between two consecutive pictures (in seconds) When Interval is not 0, capture mode is made to STILL_CAPTURE_MODE_TYPE_TIMELAPSE |
2: Capture count | min: 0 incr: 1 | Total number of images to capture. 0 to capture forever/until
|
|
3: Format | Capture format (SNAPSHOT=0, JPEG=12, JPEG_FISHEYE=13, RAW=14) | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_IMAGE_STOP_CAPTURE (Message code: 2001)¶
Stop image capture sequence.
Param: Label | Values | Units | Description |
---|---|---|---|
1: | Not used | ||
2: | Not used | ||
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_SET_VIEW_MODE (Message code: 50000)¶
Set the view mode. If view mode type is VIEW_MODE_TYPE_ROI, the region of interest must have been defined before by use of MAV_CMD_DO_SET_ROI, else view mode type is set to VIEW_MODE_TYPE_ABSOLUTE.
Param: Label | Values | Units | Description |
---|---|---|---|
1: Type | View mode type (see MAV_VIEW_MODE_TYPE) | ||
2: ROI index | Index of the ROI if view mode type is VIEW_MODE_TYPE_ROI. If ROI does not exist, consider view mode to be ABSOLUTE Empty otherwise | ||
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_CMD_SET_STILL_CAPTURE_MODE (Message code: 50001)¶
Set the still capture mode.
Param: Label | Values | Units | Description |
---|---|---|---|
1: Capture mode | Still capture mode type (see MAV_STILL_CAPTURE_MODE_TYPE | ||
2: Interval | Timelapse interval in seconds if still capture mode type is STILL_CAPTURE_MODE_TYPE_TIMELAPSE. Interval in meters between each capture if still capture mode type is STILL_CAPTURE_MODE_TYPE_GPS_POSITION. | ||
3: | Not used | ||
4: | Not used | ||
5: | Not used | ||
6: | Not used | ||
7: | Not used |
MAV_VIEW_MODE_TYPE¶
Type of the view mode. This is how the vehicle should behave to set its orientation.
Label: | Description | Values |
---|---|---|
VIEW_MODE_TYPE_ABSOLUTE | Vehicle orientation is fixed between two waypoints. Orientation is changed when the waypoint is validated. | 0 |
VIEW_MODE_TYPE_CONTINUE | Vehicle orientation changes linearly between two waypoints | 1 |
VIEW_MODE_TYPE_ROI | Vehicle orientation is given by a ROI. | 2 |
MAV_STILL_CAPTURE_MODE_TYPE¶
Type of still capture that is performed upon a still capture initiation.
Label: | Description | Values | |
---|---|---|---|
STILL_CAPTURE_MODE_TYPE_TIMELAPSE | Type of still capture that is performed upon a still capture initiation. | 0 | |
STILL_CAPTURE_MODE_TYPE_GPS_POSITION | Capture according to the GPS position of the vehicle. Images are captured with an equal spacing. | 1 |