10 #ifndef _UGCS_VSM_VEHICLE_COMMAND_H_
11 #define _UGCS_VSM_VEHICLE_COMMAND_H_
15 #include <ugcs/vsm/property.h>
97 Get_acceptance_radius()
const
99 return acceptance_radius;
118 Get_takeoff_altitude()
const
120 return takeoff_altitude;
132 Get_longitude()
const
146 Get_adsb_flight_id()
const
153 Get_adsb_registration()
const
159 Get_adsb_icao_code()
const
165 Get_adsb_operating_mode()
const
171 Get_adsb_ident_on()
const
177 Get_adsb_squawk()
const
213 Get_payload_id()
const
229 float acceptance_radius;
240 float vertical_speed = 0;
254 float takeoff_altitude;
264 mavlink::Int32 integer1;
265 mavlink::Int32 integer2;
266 mavlink::Int32 integer3;
MAVLink protocol messages.
Definition: property.h:250
Camera_power_state
Camera power state.
Definition: vehicle_command.h:36
Position< Wgs84_datum > Wgs84_position
Position defined in WGS84 geodetic system.
Definition: coordinates.h:308
Camera_trigger_state
Camera trigger state.
Definition: vehicle_command.h:25
Trigger the camera, take snapshot.
Type Get_type() const
Get type of the command.
Definition: vehicle_command.h:90
double latitude
Latitude value, radians.
Definition: coordinates.h:39
double longitude
Longitude value, radians.
Definition: coordinates.h:39
Information about a command for a vehicle.
Definition: vehicle_command.h:22
Geodetic_tuple Get_geodetic() const
Get representation in geodetic coordinates.
Definition: coordinates.h:90
Type
Type of the command.
Definition: vehicle_command.h:46
Enable direct vehicle control mode.
Coordinates manipulation.
double altitude
Altitude value, meters.
Definition: coordinates.h:39