![]() |
VSM C++ SDK
Vehicle Specific Modules SDK
|
Before commands can be issued to the vehicle VSM must inform UgCS about supported commands and mission items. This is done at the time of registering the vehicle with the system. Command registration includes description of supported parameters and their default values.
For each command vehicle supports it must send a Register_command message as part of Register_vehicle message before it can issue command via Device_command message.
Field name | Type | Description |
---|---|---|
command_id | uint32 | Registered id for command. See Commands natively supported by UgCS |
parameters | Parameter_field | List of command specific parameters |
sub_commands | Vsm_command | List of sub commands for this command. Used when command is Mission upload |
Alphabetical list of supported vehicle commands available as subcommands for Mission upload command and as standalone commands
These are the commands natively supported by UgCS (commands with known semantic). By registering command from this list VSM notifies the UgCS that vehicle is capable to execute given command with given parameters.
Command | Subsystem | In Mission | From UI | Description |
---|---|---|---|---|
adsb_set_ident | ASDB | - | + | turn IDENT on |
adsb_set_mode | ASDB | - | + | turn transponder on/off |
arm | FC | - | + | ARM command is supported |
auto | FC | - | + | Start mission flight |
camera_power | Camera | - | + | Switch camera on/off |
camera_trigger_by_distance | Camera | + | - | Trigger camera by distance |
camera_trigger_by_time | Camera | + | - | Trigger camera by time |
camera_trigger_command | Camera | - | + | Trigger camera shutter |
camera_trigger_mission | Camera | + | - | Trigger camera shutter |
direct_payload_control | Gimbal | - | + | Allows direct payload control from GS |
direct_vehicle_control | FC | - | + | Direct vehicle control (Joystick mode) |
disarm | FC | - | + | DISARM command is supported |
emergency_land | FC | - | + | Emergency land (crash landing) |
get_native_route | FC | - | + | Create route file to use with vaheicle native software |
guided | FC | - | + | Enter Click&Go mode |
joystick | FC | - | + | Enter joystick control mode |
land_command | FC | - | + | Land command |
land_mission | FC | + | - | Landing waypoint |
manual | FC | - | + | Enable manual control mode |
mission_clear | FC | - | + | Delete the route from vehicle |
mission_pause | FC | - | + | Mission can be paused from client |
mission_resume | FC | - | + | Mission can be resumed from client |
mission_upload | FC | - | + | Vehicle supports mission flight. Can contain commands marked here as available in mission. |
move | FC | + | - | Specify next waypoint and start moving towards it |
panorama | FC | + | - | Do panorama |
payload_command | PAYLOAD_CONTROLLER | - | + | Custom payload command |
payload_control | Camera | + | - | Camera control (tilt, roll, yaw, zoom) |
repeat_servo | FC | + | + | Repeat servo movement back an forth |
return_to_home | FC | - | + | Return to HOME position is supported |
select_as_video_source | Camera | - | + | Select this camera as video source |
set_fence | FC | - | + | Create cylindrical fence around home location |
set_gear_state | FC | - | + | Retract or release gear |
set_heading | FC | + | - | Set vehicle heading |
set_home | FC | + | - | Specify Home location |
set_parameter | FC, ADSB | + | + | Vehicle configuration. Contains a list of parameter definitions which can be set for the vehicle. |
set_poi | FC | + | + | Set Point Of Interest |
set_position_offset | FC | - | + | Set position offset of vehicle (i.e. moving relatively to current position) |
set_relative_heading | FC | - | + | Set heading of vehicle by turning relatively to current heading |
set_servo | FC | + | + | Set servo to given PWM value |
set_speed | FC | + | - | Set Ground speed |
set_tension | FC | - | + | Select tension value for tethered drone |
takeoff_command | FC | - | + | Takeoff command |
takeoff_mission | FC | + | - | Specify Takeoff point. |
transition_fixed | FC | + | - | Transition vehicle to fixed wing mode |
transition_vtol | FC | + | - | Transition vehicle to VTOL mode |
trigger_calibration | FC | - | + | Trigger sensor calibration |
wait | FC | + | - | Wait for specified time before proceeding to next mission item |
wait_until | FC | + | - | Wait until specified UTC time before proceeding to next mission item |
waypoint | FC | - | + | Enter Click&Go mode, specify waypoint and start moving towards it |
Other commands can be defined by VSM via Register_vehicle.register_command message.
Command ID: "adsb_set_ident"
Description: Turn on IDENT
Command has no parameters.
Command ID: "adsb_set_mode"
Description: Turn ADSB transponder on/standby/off
Parameters
Name | Type | Description |
---|---|---|
mode | FIELD_SEMANTIC_ADSB_MODE | Desired transponder mode see Adsb_mode enum |
Command ID: "arm"
Description: Arm the motors.
There are no parameters for this command.
Command ID: "auto"
Description: Put vehicle in AUTO control mode. Vehicle will setart flying mission if present.
There are no parameters for this command.
Command ID: "camera_power"
Description: Switch camera on/off
Name | Type | Description |
---|---|---|
power_state | FIELD_SEMANTIC_ENUM | See Camera power states |
Name | Value | Description |
---|---|---|
on | CAMERA_POWER_STATE_ON | Power on |
off | CAMERA_POWER_STATE_OFF | Power off |
toggle | CAMERA_POWER_STATE_TOGGLE | Switch power |
Mission item ID: "camera_trigger_by_distance"
Description: Initiate camera trigger on regular distance intervals starting from current position.
Parameters
Name | Type | Description |
---|---|---|
count | FIELD_SEMANTIC_INT | Number of consecutive trigger actions to perform. |
delay | FIELD_SEMANTIC_NUMERIC | Time in seconds to wait for the first trigger |
distance | FIELD_SEMANTIC_NUMERIC | Distance to travel in meters between consecutive triggers. |
Mission item ID: "camera_trigger_by_time"
Description: Initiate camera trigger on regular time intervals sarting from current position.
Parameters
Name | Type | Description |
---|---|---|
period | FIELD_SEMANTIC_NUMERIC | Time in seconds to wait between triggers. |
delay | FIELD_SEMANTIC_NUMERIC | Time in seconds to wait for the first trigger |
count | FIELD_SEMANTIC_INT | Number of consecutive trigger actions to perform. |
Mission item ID: "camera_trigger_command"
Description: Initiate camera trigger at current WP
Parameters
Name | Type | Description |
---|---|---|
trigger_state | FIELD_SEMANTIC_ENUM | Camera trigger state |
Name | Value | Description |
---|---|---|
video_start | CAMERA_COMMAND_TRIGGER_STATE_VIDEO_START | Start recording |
video_stop | CAMERA_COMMAND_TRIGGER_STATE_VIDEO_STOP | Stop recording or serial shooting |
single_shot | CAMERA_COMMAND_TRIGGER_STATE_SINGLE_SHOT | Take a single photo |
video_toggle | CAMERA_COMMAND_TRIGGER_STATE_VIDEO_TOGGLE | Switch video on/off |
Mission item ID: "camera_trigger_mission"
Description: Initiate camera trigger on regular time intervals sarting from current position.
Parameters
Name | Type | Description |
---|---|---|
state | FIELD_SEMANTIC_ENUM | Camera trigger state |
Name | Value | Description |
---|---|---|
on | CAMERA_MISSION_TRIGGER_STATE_ON | Start recording |
off | CAMERA_MISSION_TRIGGER_STATE_OFF | Stop recording or serial shooting |
single_photo | CAMERA_MISSION_TRIGGER_STATE_SINGLE_PHOTO | Take a single photo |
serial_photo | CAMERA_MISSION_TRIGGER_STATE_SERIAL_PHOTO | Take a series of photos |
Command ID: "direct_payload_control"
Description: Issue direct payload control command to the vehicle. Used to send joystick values to the vehicle payload.
Parameters
Name | Type | Description |
---|---|---|
pitch | FIELD_SEMANTIC_NUMERIC | pitch value [-1 .. +1] |
roll | FIELD_SEMANTIC_NUMERIC | roll value [-1 .. +1] |
yaw | FIELD_SEMANTIC_NUMERIC | yaw value [-1 .. +1] |
zoom | FIELD_SEMANTIC_NUMERIC | zoom value [-1 .. +1] |
Command ID: "direct_vehicle_control"
Description: Issue direct vehicle control command to the vehicle. Used to send joystick values to the vehicle.
Parameters
Name | Type | Description |
---|---|---|
pitch | FIELD_SEMANTIC_NUMERIC | pitch value [-1 .. +1] |
roll | FIELD_SEMANTIC_NUMERIC | roll value [-1 .. +1] |
yaw | FIELD_SEMANTIC_NUMERIC | yaw value [-1 .. +1] |
throttle | FIELD_SEMANTIC_NUMERIC | throttle value [-1 .. +1] |
Command ID: "disarm"
Description: Disarm the motors.
There are no parameters for this command.
Command ID: "emergency_land"
Description: Emergency Land. Immediately turn off motors.
There are no parameters for this command.
Command ID: "get_native_route"
Description:
Convert mission to the UTF8 text file which can be used by vehicle's native application. All mission items are added to Device_command.sub_commands list. See also supported commands. The native route file is returned via Device_response.status field.
Supported parameters:
Name | Type | Description |
---|---|---|
use_crlf | FIELD_SEMANTIC_BOOL | Line endings to be used in returned file. true: CRLF, false: LF |
Plus supports all the same parameters as Mission upload
Command ID: "guided"
Description: Put vehicle in Click&Go control mode. Vehicle can be controlled via Waypoint command command.
There are no parameters for this command.
Command ID: "joystick"
Description: Enter Joystick control mode.
There are no parameters for this command.
Command ID: "land_command"
Description: Land at current position
There are no parameters for this command.
Mission item ID: "land_mission"
Description: Specify landing position of the vehicle.
Parameters
Name | Type | Description |
---|---|---|
latitude | FIELD_SEMANTIC_LATITUDE | Geodetic latitude |
longitude | FIELD_SEMANTIC_LONGITUDE | Geodetic longitude |
altitude_amsl | FIELD_SEMANTIC_ALTITUDE_AMSL | Altitude at which to begin descent. |
descent_rate | FIELD_SEMANTIC_VERTICAL_SPEED | Descent speed in m/s |
ground_elevation | FIELD_SEMANTIC_GROUND_ELEVATION | Ground elevation at landing position (optional) |
acceptance_radius | FIELD_SEMANTIC_ACCEPTANCE_RADIUS | When the sphere with the radius centered at the target position is hit by the vehicle the target position is considered reached. |
heading | FIELD_SEMANTIC_HEADING | Vehicle heading at the WP |
Command ID: "manual"
Description: Put vehicle in MANUAL control mode. Vehicle can be controlled via RC transmitter.
There are no parameters for this command.
Command ID: "mission_clear"
Description: Deletes the current route from vehuicle.
There are no parameters for this command.
Command ID: "mission_pause"
Description: Pause mission execution (HOLD). This will put vehicle in either Click&Go or Joystick mode depending on autopilot.
There are no parameters for this command.
Command ID: "mission_resume"
Description: Continue with mission.
There are no parameters for this command.
Command ID: "mission_upload"
Description: Uploads mission to the vehicle. All mission items are added to Device_command.sub_commands list. See also supported commands.
Some vehicles will return command_map along with the response which can be used to report command from mission the vehicle is executing currently. See message @ Mission_command_map.
Supported parameters:
Name | Type | Description |
---|---|---|
altitude_origin | FIELD_SEMANTIC_ALTITUDE_AMSL | Altitude origin of the vehicle |
safe_altitude | FIELD_SEMANTIC_ALTITUDE_AMSL | Safe altitude. used for RTH and failsafe actions |
rc_loss_action | FIELD_SEMANTIC_ENUM | Failsafe action on RC loss. See Failsafe actions natively supported by UgCS |
gps_loss_action | FIELD_SEMANTIC_ENUM | Failsafe action on GPS loss. See Failsafe actions natively supported by UgCS |
low_battery_action | FIELD_SEMANTIC_ENUM | Failsafe action on low battery. See Failsafe actions natively supported by UgCS |
rth_action | FIELD_SEMANTIC_ENUM | Action after RTH. See Vehicle behavior after Return To Home |
rth_wait_altitude | FIELD_SEMANTIC_ALTITUDE_AMSL | Final altitude the drone should loiter after RTH. Used only when rth_action is "wait". |
name | FIELD_SEMANTIC_STRING | User specified mission name |
Action name | Value | Description |
---|---|---|
continue | FAILSAFE_ACTION_CONTINUE | Continue with mission. Effectively ignores the failsafe condition. |
wait | FAILSAFE_ACTION_WAIT | Wait for failsafe condition to end and then continue with mission. |
land | FAILSAFE_ACTION_LAND | Land immediately at current position. |
rth | FAILSAFE_ACTION_RTH | Climb to safe altitude defined by safe_altitude parameter and return to home position defined by Set home position mission item. |
Action name | Value | Description |
---|---|---|
land | RTH_ACTION_LAND | Descend and land |
wait | RTH_ACTION_WAIT | Do not land the vehicle but loiter at rth_wait_altitude. If rth_wait_altitude is not supported by autopilot then safe_altitude is used instead. |
Mission item ID: "move"
Description: Specifies the next waypoint. Upon encountering this item vehicle starts navigating to given coordinates using current speed and heading settings. Next mission item will be executed when vehicle arrives at the waypoint.
Supported parameters:
Name | Type | Description |
---|---|---|
latitude | FIELD_SEMANTIC_LATITUDE | Geodetic latitude |
longitude | FIELD_SEMANTIC_LONGITUDE | Geodetic longitude |
altitude_amsl | FIELD_SEMANTIC_ALTITUDE_AMSL | |
ground_elevation | FIELD_SEMANTIC_GROUND_ELEVATION | Elevation in meters (i.e. terrain height) underneath the position. |
turn_type | FIELD_SEMANTIC_ENUM | See Vehicle turn types for details |
acceptance_radius | FIELD_SEMANTIC_ACCEPTANCE_RADIUS | When the sphere with the radius centered at the target position is hit by the vehicle the target position is considered reached. |
loiter_radius | FIELD_SEMANTIC_LOITER_RADIUS | Radius of the point fly-by orbit in meters. Positive value stands for the CW direction, negative - CCW. Use 0 for no-braking pass through the target point. |
wait_time | FIELD_SEMANTIC_NUMERIC | Seconds to wait at WP before preceeding to next WP |
heading | FIELD_SEMANTIC_HEADING | Vehicle heading at the WP |
Name | Value |
---|---|
stop_and_turn | TURN_TYPE_STOP_AND_TURN |
straight | TURN_TYPE_STRAIGHT |
spline | TURN_TYPE_SPLINE |
bank_turn | TURN_TYPE_BANK_TURN |
Mission item ID: "panorama"
Description: Do panorama action.
Parameters
Name | Type | Description |
---|---|---|
angle | FIELD_SEMANTIC_NUMERIC | Target panorama angle in a range [-2Pi, 2Pi]. If positive the rotation direction should be clockwise, if negative the rotation direction should be counter-clockwise. Set in radians. |
mode | FIELD_SEMANTIC_ENUM | Camera mode. See Camera mode for panorama |
step | FIELD_SEMANTIC_NUMERIC | Absolute value of a step angle in case of a discrete shooting. Zero stands for a continuous rotation. Set in radians. |
delay | FIELD_SEMANTIC_NUMERIC | Wait time in seconds for each step. |
speed | FIELD_SEMANTIC_NUMERIC | Angular speed in rad/sec. |
Name | Value | Description |
---|---|---|
photo | PANORAMA_MODE_PHOTO | Take a photo on each step |
video | PANORAMA_MODE_VIDEO | Do not stop on each step |
Mission item ID: "payload_command"
Description: Send to onboard computer a specific payload command encoded as a byte string.
Parameters
Name | Type | Description |
---|---|---|
command | FIELD_SEMANTIC_STRING | Specific payload command arguments encoded as a byte string. |
Mission item ID: "payload_control"
Description: Move payload to given angles and zoom level. This is replacement of previous MAV_CMD_DO_PAYLOAD_CONTROL command.
Parameters
Name | Type | Description |
---|---|---|
tilt | FIELD_SEMANTIC_PITCH | Camera tilt relative to vehicle horizontal plane. Positive is up. |
roll | FIELD_SEMANTIC_ROLL | Camera roll relative to vehicle horizontal plane. Roll right is positive. |
yaw | FIELD_SEMANTIC_YAW | Camera way angle relative to vehicle nose. Positive is right. |
zoom_level | FIELD_SEMANTIC_NUMERIC | Device specific zoom value. |
Mission item ID: "repeat_servo"
Description: Move servo to given position and back the specified amount of times. Set servo to given pwm, wait for delay, set servo to default position, wait for delay.
Repeat count sets how many times to execute the above sequence. It means that after sequence finishes servo is left at default position. Deafult position is autopilot specific and cannot be specified here.
Parameters
Name | Type | Description |
---|---|---|
servo_id | FIELD_SEMANTIC_NUMERIC | Vehicle specific servo ID |
pwm | FIELD_SEMANTIC_NUMERIC | PWM rate in microseconds. Typical range is 1100..1900 |
delay | FIELD_SEMANTIC_NUMERIC | Delay in seconds |
count | FIELD_SEMANTIC_NUMERIC | How many times to repeat the sequence |
Command ID: "return_to_home"
Description: Return to Home position.
There are no parameters for this command.
Command ID: "select_as_video_source"
Description: Select this camera as source for video feed. Each camera which can be used as video source should register this command.
There are no parameters for this command.
Command ID: "set_fence"
Description: Create cylindrical fence around Home Location. RTH will be triggered if vehicle tries to leave specified limits.
Parameters
Name | Type | Description |
---|---|---|
altitude_amsl | FIELD_SEMANTIC_ALTITUDE_AMSL | Fence altitude in meters |
altitude_origin | FIELD_SEMANTIC_ALTITUDE_AMSL | Altitude origin in meters AMSL. Typically this should be the HL altitude. |
radius | FIELD_SEMANTIC_NUMERIC | FEnce radius in meters. Max ground distance from Home Location |
Command ID: "set_gear_state"
Description: Retract or release gear
Parameters
Name | Type | Description |
---|---|---|
release | FIELD_SEMANTIC_BOOL | true - release gear, false - retract gear |
Mission item ID: "set_heading"
Description: Change the heading of vehicle. This makes sense only for copter style vehicles when heading does not specify direction of flight.
IMPORTANT: "heading" mission item overrides any heading changes which are implicitly specified by payload control mission items in case payload yaw is controlled by vehicle heading.
Parameters
Name | Type | Description |
---|---|---|
heading | FIELD_SEMANTIC_HEADING | Heading angle in radians from North |
Mission item ID: "set_home"
Description: Specify home position of the vehicle. This is the location the vehicle will return on Return_To_Home command or in case of failsafe event and when failsafe is set to return to home.
Parameters
Name | Type | Description |
---|---|---|
latitude | FIELD_SEMANTIC_LATITUDE | Geodetic latitude |
longitude | FIELD_SEMANTIC_LONGITUDE | Geodetic longitude |
altitude_amsl | FIELD_SEMANTIC_ALTITUDE_AMSL | Home position altitude |
ground_elevation | FIELD_SEMANTIC_GROUND_ELEVATION | Ground elevation at home position (optional) |
List of supported payload mission items with detailed description of each item in the following sections.
Mission item ID: "set_parameter"
Description: Set vehicle parameters.
Supported FC parameters:
Name | Type | Description |
---|---|---|
landing_flare_altitude | FIELD_SEMANTIC_NUMERIC | |
landing_flare_time | FIELD_SEMANTIC_NUMERIC | |
min_landing_pitch | FIELD_SEMANTIC_NUMERIC | |
landing_flare_damp | FIELD_SEMANTIC_NUMERIC | |
landing_approach_airspeed | FIELD_SEMANTIC_NUMERIC | |
landing_speed_weighting | FIELD_SEMANTIC_NUMERIC | |
max_auto_flight_pitch | FIELD_SEMANTIC_NUMERIC | |
max_pitch | FIELD_SEMANTIC_NUMERIC | |
min_throttle | FIELD_SEMANTIC_NUMERIC | |
landing_sink_rate | FIELD_SEMANTIC_NUMERIC | |
landing_rangefinder_enabled | FIELD_SEMANTIC_NUMERIC | |
min_rangefinder_distance | FIELD_SEMANTIC_NUMERIC |
Supported ADSB parameters:
Name | Type | Description |
---|---|---|
adsb_icao | FIELD_SEMANTIC_NUMERIC | 24 bit integer |
adsb_registration | FIELD_SEMANTIC_STRING | |
adsb_flight_id | FIELD_SEMANTIC_STRING | |
adsb_squawk | FIELD_SEMANTIC_NUMERIC | 12 bit integer |
Mission item ID: "set_poi"
Description: Set Point Of Interest.
Parameters
Name | Type | Description |
---|---|---|
latitude | FIELD_SEMANTIC_LATITUDE | Geodetic latitude |
longitude | FIELD_SEMANTIC_LONGITUDE | Geodetic longitude |
altitude_amsl | FIELD_SEMANTIC_ALTITUDE_AMSL | Altitude AMSL |
active | FIELD_SEMANTIC_BOOL | true: start poi, false: end poi action. |
Command ID: "set_position_offset"
Description: Issue vehicle to change it position relatively to current position in body frame.
Parameters
Name | Type | Description |
---|---|---|
x | FIELD_SEMANTIC_NUMERIC | offset in X-axis in meters (positive - forward) |
y | FIELD_SEMANTIC_NUMERIC | offset in Y-axis in meters (positive - right) |
z | FIELD_SEMANTIC_NUMERIC | offset in Z-axis in meters (positive - down) |
Command ID: "set_relative_heading"
Description: Issue vehicle to change it heading relatively to current heading.
Parameters
Name | Type | Description |
---|---|---|
relative_heading | FIELD_SEMANTIC_NUMERIC | turning around Z-Axis in radians relative to current heading (positive - CW) |
Mission item ID: "set_servo"
Description: Move servo to given position and hold.
Parameters
Name | Type | Description |
---|---|---|
servo_id | FIELD_SEMANTIC_NUMERIC | Vehicle specific servo ID |
pwm | FIELD_SEMANTIC_NUMERIC | PWM rate in microseconds. Typical range is 1100..1900 |
Mission item ID: "set_speed"
Description: Set the maximum ground speed which will be used by vehicle from now on. This is the horizontal component of speed.
Parameters
Name | Type | Description |
---|---|---|
ground_speed | FIELD_SEMANTIC_GROUND_SPEED | Ground speed in m/s |
vertical_speed | FIELD_SEMANTIC_VERTICAL_SPEED | Climb speed in m/s |
Command ID: "set_tension"
Description: Set tension value for the winch in Newtons
Parameters
Name | Type | Description |
---|---|---|
tension | FIELD_SEMANTIC_NUMERIC | tension value |
Command ID: "takeoff_command"
Description: Takeoff from current position
Parameters
Name | Type | Description |
---|---|---|
relative_altitude | FIELD_SEMANTIC_ALTITUDE_RAW, META_VALUE_NA | relative altitude for takeoff |
Mission item ID: "takeoff_mission"
Description: Specify takeoff position of the vehicle.
Parameters
Name | Type | Description |
---|---|---|
latitude | FIELD_SEMANTIC_LATITUDE | Geodetic latitude |
longitude | FIELD_SEMANTIC_LONGITUDE | Geodetic longitude |
altitude_amsl | FIELD_SEMANTIC_ALTITUDE_AMSL | Takeoff target altitude. Vehicle will ascend to this altitude before proceeding to given latitude and longitude. If vehicle is airborne and is above target altitude it will proceed to given latitude and longitude immediately. |
climb_rate | FIELD_SEMANTIC_VERTICAL_SPEED | Climb speed in m/s |
ground_elevation | FIELD_SEMANTIC_GROUND_ELEVATION | Ground elevation at takeoff position (optional) |
acceptance_radius | FIELD_SEMANTIC_ACCEPTANCE_RADIUS | When the sphere with the radius centered at the target position is hit by the vehicle the target position is considered reached. |
heading | FIELD_SEMANTIC_HEADING | Vehicle heading at the WP |
Mission item ID: "transition_fixed"
Description: Put the fixed wing VTOL capable vehicle in fixed wing flight mode.
Mission item ID: "transition_vtol"
Description: Put the fixed wing VTOL capable vehicle in copter-like mode.
Mission item ID: "trigger_calibration"
Description: Starts vehicle sensor calibration sequence. Vehicle must be stationary in on the ground, disarmed.
Mission item ID: "wait"
Description: Wait for given number of seconds in current position before continuing with next mission item. Specify time==N/A to wait indefinitely.
Parameters
Name | Type | Description |
---|---|---|
time | FIELD_SEMANTIC_NUMERIC | Number of seconds to wait. If the field value is N/A, then wait indefinitely. |
Mission item ID: "wait_until"
Description: Wait until given time before continuing with next mission item. Specify time==N/A to wait indefinitely.
Parameters
Name | Type | Description |
---|---|---|
time | FIELD_SEMANTIC_TIMESTAMP | Milliseconds of UTC time since Unix epoch (1970-01-01T00:00:00Z) |
Command ID: "waypoint"
Description: Specifies the single waypoint. Used while vehicle is in Click&Go control mode.
Supported parameters:
Name | Type | Description |
---|---|---|
latitude | FIELD_SEMANTIC_LATITUDE | Geodetic latitude |
longitude | FIELD_SEMANTIC_LONGITUDE | Geodetic longitude |
altitude_amsl | FIELD_SEMANTIC_ALTITUDE_AMSL | |
altitude_origin | FIELD_SEMANTIC_ALTITUDE_AMSL | Altitude origin of the vehicle |
ground_speed | FIELD_SEMANTIC_GROUND_SPEED | Ground speed in m/s |
vertical_speed | FIELD_SEMANTIC_VERTICAL_SPEED | Climb speed in m/s |
acceptance_radius | FIELD_SEMANTIC_ACCEPTANCE_RADIUS | When the sphere with the radius centered at the target position is hit by the vehicle the target position is considered reached. |
heading | FIELD_SEMANTIC_HEADING | Vehicle heading at the WP |