mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-18 02:07:35 +08:00
AUTOMATED code-style fix on topics. NO MANUAL OR SEMANTIC EDITS
This commit is contained in:
@@ -60,7 +60,7 @@
|
||||
enum ESC_VENDOR {
|
||||
ESC_VENDOR_GENERIC = 0, /**< generic ESC */
|
||||
ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */
|
||||
ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
|
||||
ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
|
||||
};
|
||||
|
||||
enum ESC_CONNECTION_TYPE {
|
||||
@@ -79,16 +79,15 @@ enum ESC_CONNECTION_TYPE {
|
||||
/**
|
||||
* Electronic speed controller status.
|
||||
*/
|
||||
struct esc_status_s
|
||||
{
|
||||
struct esc_status_s {
|
||||
/* use of a counter and timestamp recommended (but not necessary) */
|
||||
|
||||
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
|
||||
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
|
||||
|
||||
|
||||
uint8_t esc_count; /**< number of connected ESCs */
|
||||
enum ESC_CONNECTION_TYPE esc_connectiontype; /**< how ESCs connected to the system */
|
||||
|
||||
|
||||
struct {
|
||||
uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */
|
||||
enum ESC_VENDOR esc_vendor; /**< Vendor of current ESC */
|
||||
|
||||
@@ -53,8 +53,7 @@
|
||||
/**
|
||||
* Filtered bottom flow in bodyframe.
|
||||
*/
|
||||
struct filtered_bottom_flow_s
|
||||
{
|
||||
struct filtered_bottom_flow_s {
|
||||
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
|
||||
|
||||
float sumx; /**< Integrated bodyframe x flow in meters */
|
||||
|
||||
@@ -53,11 +53,10 @@
|
||||
/**
|
||||
* GPS home position in WGS84 coordinates.
|
||||
*/
|
||||
struct home_position_s
|
||||
{
|
||||
struct home_position_s {
|
||||
uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
|
||||
uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp from the gps module */
|
||||
|
||||
|
||||
int32_t lat; /**< Latitude in 1E7 degrees */
|
||||
int32_t lon; /**< Longitude in 1E7 degrees */
|
||||
int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
|
||||
|
||||
@@ -67,8 +67,7 @@ enum NAV_CMD {
|
||||
* This is the position the MAV is heading towards. If it of type loiter,
|
||||
* the MAV is circling around it with the given loiter radius in meters.
|
||||
*/
|
||||
struct mission_item_s
|
||||
{
|
||||
struct mission_item_s {
|
||||
bool altitude_is_relative; /**< true if altitude is relative from start point */
|
||||
double lat; /**< latitude in degrees * 1E7 */
|
||||
double lon; /**< longitude in degrees * 1E7 */
|
||||
@@ -83,8 +82,7 @@ struct mission_item_s
|
||||
float param4;
|
||||
};
|
||||
|
||||
struct mission_s
|
||||
{
|
||||
struct mission_s {
|
||||
struct mission_item_s *items;
|
||||
unsigned count;
|
||||
};
|
||||
|
||||
@@ -52,7 +52,7 @@
|
||||
* Airspeed
|
||||
*/
|
||||
struct navigation_capabilities_s {
|
||||
float turn_distance; /**< the optimal distance to a waypoint to switch to the next */
|
||||
float turn_distance; /**< the optimal distance to a waypoint to switch to the next */
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@@ -45,12 +45,11 @@
|
||||
|
||||
/**
|
||||
* Off-board control inputs.
|
||||
*
|
||||
*
|
||||
* Typically sent by a ground control station / joystick or by
|
||||
* some off-board controller via C or SIMULINK.
|
||||
*/
|
||||
enum OFFBOARD_CONTROL_MODE
|
||||
{
|
||||
enum OFFBOARD_CONTROL_MODE {
|
||||
OFFBOARD_CONTROL_MODE_DIRECT = 0,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_RATES = 1,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE = 2,
|
||||
|
||||
@@ -52,29 +52,28 @@
|
||||
*/
|
||||
#define RC_CHANNELS_MAPPED_MAX 15
|
||||
|
||||
/**
|
||||
/**
|
||||
* This defines the mapping of the RC functions.
|
||||
* The value assigned to the specific function corresponds to the entry of
|
||||
* the channel array chan[].
|
||||
*/
|
||||
enum RC_CHANNELS_FUNCTION
|
||||
{
|
||||
THROTTLE = 0,
|
||||
ROLL = 1,
|
||||
PITCH = 2,
|
||||
YAW = 3,
|
||||
MODE = 4,
|
||||
RETURN = 5,
|
||||
ASSISTED = 6,
|
||||
MISSION = 7,
|
||||
OFFBOARD_MODE = 8,
|
||||
FLAPS = 9,
|
||||
AUX_1 = 10,
|
||||
AUX_2 = 11,
|
||||
AUX_3 = 12,
|
||||
AUX_4 = 13,
|
||||
AUX_5 = 14,
|
||||
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
|
||||
enum RC_CHANNELS_FUNCTION {
|
||||
THROTTLE = 0,
|
||||
ROLL = 1,
|
||||
PITCH = 2,
|
||||
YAW = 3,
|
||||
MODE = 4,
|
||||
RETURN = 5,
|
||||
ASSISTED = 6,
|
||||
MISSION = 7,
|
||||
OFFBOARD_MODE = 8,
|
||||
FLAPS = 9,
|
||||
AUX_1 = 10,
|
||||
AUX_2 = 11,
|
||||
AUX_3 = 12,
|
||||
AUX_4 = 13,
|
||||
AUX_5 = 14,
|
||||
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
|
||||
};
|
||||
|
||||
/**
|
||||
@@ -85,16 +84,16 @@ enum RC_CHANNELS_FUNCTION
|
||||
struct rc_channels_s {
|
||||
|
||||
uint64_t timestamp; /**< In microseconds since boot time. */
|
||||
uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
|
||||
struct {
|
||||
float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
|
||||
} chan[RC_CHANNELS_MAPPED_MAX];
|
||||
uint8_t chan_count; /**< number of valid channels */
|
||||
uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
|
||||
struct {
|
||||
float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
|
||||
} chan[RC_CHANNELS_MAPPED_MAX];
|
||||
uint8_t chan_count; /**< number of valid channels */
|
||||
|
||||
/*String array to store the names of the functions*/
|
||||
char function_name[RC_CHANNELS_FUNCTION_MAX][20];
|
||||
int8_t function[RC_CHANNELS_FUNCTION_MAX];
|
||||
uint8_t rssi; /**< Overall receive signal strength */
|
||||
/*String array to store the names of the functions*/
|
||||
char function_name[RC_CHANNELS_FUNCTION_MAX][20];
|
||||
int8_t function[RC_CHANNELS_FUNCTION_MAX];
|
||||
uint8_t rssi; /**< Overall receive signal strength */
|
||||
}; /**< radio control channels. */
|
||||
|
||||
/**
|
||||
|
||||
@@ -50,8 +50,7 @@
|
||||
#include <stdbool.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
enum SUBSYSTEM_TYPE
|
||||
{
|
||||
enum SUBSYSTEM_TYPE {
|
||||
SUBSYSTEM_TYPE_GYRO = 1,
|
||||
SUBSYSTEM_TYPE_ACC = 2,
|
||||
SUBSYSTEM_TYPE_MAG = 4,
|
||||
|
||||
@@ -44,10 +44,10 @@
|
||||
#include "../uORB.h"
|
||||
|
||||
enum TELEMETRY_STATUS_RADIO_TYPE {
|
||||
TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0,
|
||||
TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO,
|
||||
TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET,
|
||||
TELEMETRY_STATUS_RADIO_TYPE_WIRE
|
||||
TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0,
|
||||
TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO,
|
||||
TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET,
|
||||
TELEMETRY_STATUS_RADIO_TYPE_WIRE
|
||||
};
|
||||
|
||||
/**
|
||||
@@ -57,14 +57,14 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
|
||||
|
||||
struct telemetry_status_s {
|
||||
uint64_t timestamp;
|
||||
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
|
||||
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
|
||||
unsigned rssi; /**< local signal strength */
|
||||
unsigned remote_rssi; /**< remote signal strength */
|
||||
unsigned rxerrors; /**< receive errors */
|
||||
unsigned fixed; /**< count of error corrected packets */
|
||||
uint8_t noise; /**< background noise level */
|
||||
uint8_t remote_noise; /**< remote background noise level */
|
||||
uint8_t txbuf; /**< how full the tx buffer is as a percentage */
|
||||
unsigned remote_rssi; /**< remote signal strength */
|
||||
unsigned rxerrors; /**< receive errors */
|
||||
unsigned fixed; /**< count of error corrected packets */
|
||||
uint8_t noise; /**< background noise level */
|
||||
uint8_t remote_noise; /**< remote background noise level */
|
||||
uint8_t txbuf; /**< how full the tx buffer is as a percentage */
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@@ -52,8 +52,7 @@
|
||||
/**
|
||||
* vehicle attitude setpoint.
|
||||
*/
|
||||
struct vehicle_attitude_setpoint_s
|
||||
{
|
||||
struct vehicle_attitude_setpoint_s {
|
||||
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
|
||||
|
||||
float roll_body; /**< body angle in NED frame */
|
||||
|
||||
@@ -48,8 +48,7 @@
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct vehicle_bodyframe_speed_setpoint_s
|
||||
{
|
||||
struct vehicle_bodyframe_speed_setpoint_s {
|
||||
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
|
||||
|
||||
float vx; /**< in m/s */
|
||||
|
||||
@@ -51,43 +51,42 @@
|
||||
* Should contain all commands from MAVLink's VEHICLE_CMD ENUM,
|
||||
* but can contain additional ones.
|
||||
*/
|
||||
enum VEHICLE_CMD
|
||||
{
|
||||
VEHICLE_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_ROI=80, /* 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. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
||||
VEHICLE_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
|
||||
VEHICLE_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
|
||||
VEHICLE_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
|
||||
VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
|
||||
VEHICLE_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
|
||||
VEHICLE_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
|
||||
VEHICLE_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
|
||||
VEHICLE_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
|
||||
VEHICLE_CMD_ENUM_END=501, /* | */
|
||||
enum VEHICLE_CMD {
|
||||
VEHICLE_CMD_NAV_WAYPOINT = 16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_UNLIM = 17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_TURNS = 18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_TIME = 19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_LAND = 21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_TAKEOFF = 22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_ROI = 80, /* 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. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
||||
VEHICLE_CMD_NAV_PATHPLANNING = 81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
|
||||
VEHICLE_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_DELAY = 112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_CHANGE_ALT = 113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
|
||||
VEHICLE_CMD_CONDITION_DISTANCE = 114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_YAW = 115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_LAST = 159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_MODE = 176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_JUMP = 177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_CHANGE_SPEED = 178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_HOME = 179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_DO_SET_PARAMETER = 180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_RELAY = 181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_REPEAT_RELAY = 182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_SET_SERVO = 183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_REPEAT_SERVO = 184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_CONTROL_VIDEO = 200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_DO_LAST = 240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
|
||||
VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
|
||||
VEHICLE_CMD_PREFLIGHT_STORAGE = 245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_OVERRIDE_GOTO = 252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
|
||||
VEHICLE_CMD_MISSION_START = 300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
|
||||
VEHICLE_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
|
||||
VEHICLE_CMD_START_RX_PAIR = 500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
|
||||
VEHICLE_CMD_ENUM_END = 501, /* | */
|
||||
};
|
||||
|
||||
/**
|
||||
@@ -96,14 +95,13 @@ enum VEHICLE_CMD
|
||||
* Should contain all of MAVLink's VEHICLE_CMD_RESULT values
|
||||
* but can contain additional ones.
|
||||
*/
|
||||
enum VEHICLE_CMD_RESULT
|
||||
{
|
||||
VEHICLE_CMD_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
|
||||
VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
|
||||
VEHICLE_CMD_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */
|
||||
VEHICLE_CMD_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
|
||||
VEHICLE_CMD_RESULT_FAILED=4, /* Command executed, but failed | */
|
||||
VEHICLE_CMD_RESULT_ENUM_END=5, /* | */
|
||||
enum VEHICLE_CMD_RESULT {
|
||||
VEHICLE_CMD_RESULT_ACCEPTED = 0, /* Command ACCEPTED and EXECUTED | */
|
||||
VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1, /* Command TEMPORARY REJECTED/DENIED | */
|
||||
VEHICLE_CMD_RESULT_DENIED = 2, /* Command PERMANENTLY DENIED | */
|
||||
VEHICLE_CMD_RESULT_UNSUPPORTED = 3, /* Command UNKNOWN/UNSUPPORTED | */
|
||||
VEHICLE_CMD_RESULT_FAILED = 4, /* Command executed, but failed | */
|
||||
VEHICLE_CMD_RESULT_ENUM_END = 5, /* | */
|
||||
};
|
||||
|
||||
/**
|
||||
@@ -111,8 +109,7 @@ enum VEHICLE_CMD_RESULT
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct vehicle_command_s
|
||||
{
|
||||
struct vehicle_command_s {
|
||||
float param1; /**< Parameter 1, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
float param2; /**< Parameter 2, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
float param3; /**< Parameter 3, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
|
||||
@@ -47,8 +47,7 @@
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
struct vehicle_control_debug_s
|
||||
{
|
||||
struct vehicle_control_debug_s {
|
||||
uint64_t timestamp; /**< in microseconds since system start */
|
||||
|
||||
float roll_p; /**< roll P control part */
|
||||
@@ -77,9 +76,9 @@ struct vehicle_control_debug_s
|
||||
|
||||
}; /**< vehicle_control_debug */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* register this as object request broker structure */
|
||||
ORB_DECLARE(vehicle_control_debug);
|
||||
|
||||
@@ -38,7 +38,7 @@
|
||||
/**
|
||||
* @file vehicle_control_mode.h
|
||||
* Definition of the vehicle_control_mode uORB topic.
|
||||
*
|
||||
*
|
||||
* All control apps should depend their actions based on the flags set here.
|
||||
*/
|
||||
|
||||
@@ -59,8 +59,7 @@
|
||||
*
|
||||
* Encodes the complete system state and is set by the commander app.
|
||||
*/
|
||||
struct vehicle_control_mode_s
|
||||
{
|
||||
struct vehicle_control_mode_s {
|
||||
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
|
||||
|
||||
bool flag_armed;
|
||||
|
||||
@@ -51,16 +51,15 @@
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* Fused global position in WGS84.
|
||||
*
|
||||
* This struct contains the system's believ about its position. It is not the raw GPS
|
||||
* measurement (@see vehicle_gps_position). This topic is usually published by the position
|
||||
* estimator, which will take more sources of information into account than just GPS,
|
||||
* e.g. control inputs of the vehicle in a Kalman-filter implementation.
|
||||
*/
|
||||
struct vehicle_global_position_s
|
||||
{
|
||||
/**
|
||||
* Fused global position in WGS84.
|
||||
*
|
||||
* This struct contains the system's believ about its position. It is not the raw GPS
|
||||
* measurement (@see vehicle_gps_position). This topic is usually published by the position
|
||||
* estimator, which will take more sources of information into account than just GPS,
|
||||
* e.g. control inputs of the vehicle in a Kalman-filter implementation.
|
||||
*/
|
||||
struct vehicle_global_position_s {
|
||||
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
|
||||
uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
|
||||
bool valid; /**< true if position satisfies validity criteria of estimator */
|
||||
|
||||
@@ -58,8 +58,7 @@
|
||||
*
|
||||
* This are the three next waypoints (or just the next two or one).
|
||||
*/
|
||||
struct vehicle_global_position_set_triplet_s
|
||||
{
|
||||
struct vehicle_global_position_set_triplet_s {
|
||||
bool previous_valid; /**< flag indicating previous position is valid */
|
||||
bool next_valid; /**< flag indicating next position is valid */
|
||||
|
||||
|
||||
@@ -58,8 +58,7 @@
|
||||
* This is the position the MAV is heading towards. If it of type loiter,
|
||||
* the MAV is circling around it with the given loiter radius in meters.
|
||||
*/
|
||||
struct vehicle_global_position_setpoint_s
|
||||
{
|
||||
struct vehicle_global_position_setpoint_s {
|
||||
bool altitude_is_relative; /**< true if altitude is relative from start point */
|
||||
int32_t lat; /**< latitude in degrees * 1E7 */
|
||||
int32_t lon; /**< longitude in degrees * 1E7 */
|
||||
|
||||
@@ -47,8 +47,7 @@
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct vehicle_global_velocity_setpoint_s
|
||||
{
|
||||
struct vehicle_global_velocity_setpoint_s {
|
||||
float vx; /**< in m/s NED */
|
||||
float vy; /**< in m/s NED */
|
||||
float vz; /**< in m/s NED */
|
||||
|
||||
@@ -53,13 +53,12 @@
|
||||
/**
|
||||
* GPS position in WGS84 coordinates.
|
||||
*/
|
||||
struct vehicle_gps_position_s
|
||||
{
|
||||
struct vehicle_gps_position_s {
|
||||
uint64_t timestamp_position; /**< Timestamp for position information */
|
||||
int32_t lat; /**< Latitude in 1E-7 degrees */
|
||||
int32_t lon; /**< Longitude in 1E-7 degrees */
|
||||
int32_t alt; /**< Altitude in 1E-3 meters (millimeters) above MSL */
|
||||
|
||||
|
||||
uint64_t timestamp_variance;
|
||||
float s_variance_m_s; /**< speed accuracy estimate m/s */
|
||||
float p_variance_m; /**< position accuracy estimate m */
|
||||
|
||||
@@ -52,8 +52,7 @@
|
||||
/**
|
||||
* Fused local position in NED.
|
||||
*/
|
||||
struct vehicle_local_position_s
|
||||
{
|
||||
struct vehicle_local_position_s {
|
||||
uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
|
||||
bool xy_valid; /**< true if x and y are valid */
|
||||
bool z_valid; /**< true if z is valid */
|
||||
|
||||
@@ -49,8 +49,7 @@
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct vehicle_local_position_setpoint_s
|
||||
{
|
||||
struct vehicle_local_position_setpoint_s {
|
||||
float x; /**< in meters NED */
|
||||
float y; /**< in meters NED */
|
||||
float z; /**< in meters NED */
|
||||
|
||||
@@ -47,8 +47,7 @@
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
struct vehicle_rates_setpoint_s
|
||||
{
|
||||
struct vehicle_rates_setpoint_s {
|
||||
uint64_t timestamp; /**< in microseconds since system start */
|
||||
|
||||
float roll; /**< body angular rates in NED frame */
|
||||
@@ -58,9 +57,9 @@ struct vehicle_rates_setpoint_s
|
||||
|
||||
}; /**< vehicle_rates_setpoint */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* register this as object request broker structure */
|
||||
ORB_DECLARE(vehicle_rates_setpoint);
|
||||
|
||||
@@ -131,31 +131,31 @@ enum VEHICLE_MODE_FLAG {
|
||||
* Should match 1:1 MAVLink's MAV_TYPE ENUM
|
||||
*/
|
||||
enum VEHICLE_TYPE {
|
||||
VEHICLE_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
|
||||
VEHICLE_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
|
||||
VEHICLE_TYPE_QUADROTOR=2, /* Quadrotor | */
|
||||
VEHICLE_TYPE_COAXIAL=3, /* Coaxial helicopter | */
|
||||
VEHICLE_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
|
||||
VEHICLE_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
|
||||
VEHICLE_TYPE_GCS=6, /* Operator control unit / ground control station | */
|
||||
VEHICLE_TYPE_AIRSHIP=7, /* Airship, controlled | */
|
||||
VEHICLE_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
|
||||
VEHICLE_TYPE_ROCKET=9, /* Rocket | */
|
||||
VEHICLE_TYPE_GROUND_ROVER=10, /* Ground rover | */
|
||||
VEHICLE_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
|
||||
VEHICLE_TYPE_SUBMARINE=12, /* Submarine | */
|
||||
VEHICLE_TYPE_HEXAROTOR=13, /* Hexarotor | */
|
||||
VEHICLE_TYPE_OCTOROTOR=14, /* Octorotor | */
|
||||
VEHICLE_TYPE_TRICOPTER=15, /* Octorotor | */
|
||||
VEHICLE_TYPE_FLAPPING_WING=16, /* Flapping wing | */
|
||||
VEHICLE_TYPE_KITE=17, /* Kite | */
|
||||
VEHICLE_TYPE_ENUM_END=18, /* | */
|
||||
VEHICLE_TYPE_GENERIC = 0, /* Generic micro air vehicle. | */
|
||||
VEHICLE_TYPE_FIXED_WING = 1, /* Fixed wing aircraft. | */
|
||||
VEHICLE_TYPE_QUADROTOR = 2, /* Quadrotor | */
|
||||
VEHICLE_TYPE_COAXIAL = 3, /* Coaxial helicopter | */
|
||||
VEHICLE_TYPE_HELICOPTER = 4, /* Normal helicopter with tail rotor. | */
|
||||
VEHICLE_TYPE_ANTENNA_TRACKER = 5, /* Ground installation | */
|
||||
VEHICLE_TYPE_GCS = 6, /* Operator control unit / ground control station | */
|
||||
VEHICLE_TYPE_AIRSHIP = 7, /* Airship, controlled | */
|
||||
VEHICLE_TYPE_FREE_BALLOON = 8, /* Free balloon, uncontrolled | */
|
||||
VEHICLE_TYPE_ROCKET = 9, /* Rocket | */
|
||||
VEHICLE_TYPE_GROUND_ROVER = 10, /* Ground rover | */
|
||||
VEHICLE_TYPE_SURFACE_BOAT = 11, /* Surface vessel, boat, ship | */
|
||||
VEHICLE_TYPE_SUBMARINE = 12, /* Submarine | */
|
||||
VEHICLE_TYPE_HEXAROTOR = 13, /* Hexarotor | */
|
||||
VEHICLE_TYPE_OCTOROTOR = 14, /* Octorotor | */
|
||||
VEHICLE_TYPE_TRICOPTER = 15, /* Octorotor | */
|
||||
VEHICLE_TYPE_FLAPPING_WING = 16, /* Flapping wing | */
|
||||
VEHICLE_TYPE_KITE = 17, /* Kite | */
|
||||
VEHICLE_TYPE_ENUM_END = 18, /* | */
|
||||
};
|
||||
|
||||
enum VEHICLE_BATTERY_WARNING {
|
||||
VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
|
||||
VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
|
||||
VEHICLE_BATTERY_WARNING_CRITICAL /**< alerting of critical voltage */
|
||||
VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
|
||||
VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
|
||||
VEHICLE_BATTERY_WARNING_CRITICAL /**< alerting of critical voltage */
|
||||
};
|
||||
|
||||
/**
|
||||
@@ -168,8 +168,7 @@ enum VEHICLE_BATTERY_WARNING {
|
||||
*
|
||||
* Encodes the complete system state and is set by the commander app.
|
||||
*/
|
||||
struct vehicle_status_s
|
||||
{
|
||||
struct vehicle_status_s {
|
||||
/* use of a counter and timestamp recommended (but not necessary) */
|
||||
|
||||
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
|
||||
@@ -216,7 +215,7 @@ struct vehicle_status_s
|
||||
uint32_t onboard_control_sensors_present;
|
||||
uint32_t onboard_control_sensors_enabled;
|
||||
uint32_t onboard_control_sensors_health;
|
||||
|
||||
|
||||
float load; /**< processor load from 0 to 1 */
|
||||
float battery_voltage;
|
||||
float battery_current;
|
||||
|
||||
@@ -52,8 +52,7 @@
|
||||
/**
|
||||
* Fused local position in NED.
|
||||
*/
|
||||
struct vehicle_vicon_position_s
|
||||
{
|
||||
struct vehicle_vicon_position_s {
|
||||
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
|
||||
bool valid; /**< true if position satisfies validity criteria of estimator */
|
||||
|
||||
|
||||
Reference in New Issue
Block a user