103 changed files with 925 additions and 2255 deletions
@ -0,0 +1,4 @@
@@ -0,0 +1,4 @@
|
||||
uint8 NUM_ACTUATORS_DIRECT = 16 |
||||
uint64 timestamp # timestamp in us since system boot |
||||
uint32 nvalues # number of valid values |
||||
float32[16] values # actuator values, from -1 to 1 |
@ -0,0 +1,5 @@
@@ -0,0 +1,5 @@
|
||||
uint8 NUM_ACTUATOR_OUTPUTS = 16 |
||||
uint8 NUM_ACTUATOR_OUTPUT_GROUPS = 4 # for sanity checking |
||||
uint64 timestamp # output timestamp in us since system boot |
||||
uint32 noutputs # valid outputs |
||||
float32[16] output # output data, in natural output units |
@ -0,0 +1,4 @@
@@ -0,0 +1,4 @@
|
||||
uint64 timestamp # microseconds since system boot, needed to integrate |
||||
float32 indicated_airspeed_m_s # indicated airspeed in meters per second, -1 if unknown |
||||
float32 true_airspeed_m_s # true airspeed in meters per second, -1 if unknown |
||||
float32 air_temperature_celsius # air temperature in degrees celsius, -1000 if unknown |
@ -0,0 +1,5 @@
@@ -0,0 +1,5 @@
|
||||
uint64 timestamp # microseconds since system boot, needed to integrate |
||||
float32 voltage_v # Battery voltage in volts, 0 if unknown |
||||
float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown |
||||
float32 current_a # Battery current in amperes, -1 if unknown |
||||
float32 discharged_mah # Discharged amount in mAh, -1 if unknown |
@ -0,0 +1,3 @@
@@ -0,0 +1,3 @@
|
||||
uint32 timestamp_ms # in milliseconds since system start |
||||
int8[10] key # max. 10 characters as key / name |
||||
float32 value # the value to send as debug output |
@ -0,0 +1,6 @@
@@ -0,0 +1,6 @@
|
||||
uint64 timestamp # Microseconds since system boot, needed to integrate |
||||
uint64 error_count # Number of errors detected by driver |
||||
float32 differential_pressure_raw_pa # Raw differential pressure reading (may be negative) |
||||
float32 differential_pressure_filtered_pa # Low pass filtered differential pressure reading |
||||
float32 max_differential_pressure_pa # Maximum differential pressure reading |
||||
float32 temperature # Temperature provided by sensor, -1000.0f if unknown |
@ -0,0 +1,5 @@
@@ -0,0 +1,5 @@
|
||||
uint8 NUM_ENCODERS = 4 |
||||
|
||||
uint64 timestamp |
||||
int64[4] counts # counts of encoder |
||||
float32[4] velocity # counts of encoder/ second |
@ -0,0 +1,11 @@
@@ -0,0 +1,11 @@
|
||||
uint8 esc_vendor # Vendor of current ESC |
||||
uint32 esc_errorcount # Number of reported errors by ESC - if supported |
||||
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported |
||||
float32 esc_voltage # Voltage measured from current ESC [V] - if supported |
||||
float32 esc_current # Current measured from current ESC [A] - if supported |
||||
float32 esc_temperature # Temperature measured from current ESC [degC] - if supported |
||||
float32 esc_setpoint # setpoint of current ESC |
||||
uint16 esc_setpoint_raw # setpoint of current ESC (Value sent to ESC) |
||||
uint16 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver) |
||||
uint16 esc_version # Version of current ESC - if supported |
||||
uint16 esc_state # State of ESC - depend on Vendor |
@ -0,0 +1,19 @@
@@ -0,0 +1,19 @@
|
||||
uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs |
||||
|
||||
uint8 ESC_VENDOR_GENERIC = 0 # generic ESC |
||||
uint8 ESC_VENDOR_MIKROKOPTER = 1 # Mikrokopter |
||||
uint8 ESC_VENDOR_GRAUPNER_HOTT = 2 # Graupner HoTT ESC |
||||
|
||||
uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC |
||||
uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC |
||||
uint8 ESC_CONNECTION_TYPE_ONESHOOT = 2 # One Shoot PPM |
||||
uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C |
||||
uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus |
||||
|
||||
uint16 counter # incremented by the writing thread everytime new data is stored |
||||
uint64 timestamp # in microseconds since system start, is set whenever the writing thread stores new data |
||||
|
||||
uint8 esc_count # number of connected ESCs |
||||
uint8 esc_connectiontype # how ESCs connected to the system |
||||
|
||||
esc_report[8] esc |
@ -0,0 +1,6 @@
@@ -0,0 +1,6 @@
|
||||
uint64 timestamp # Timestamp in microseconds since boot |
||||
float32[32] states # Internal filter states |
||||
float32 n_states # Number of states effectively used |
||||
uint8 nan_flags # Bitmask to indicate NaN states |
||||
uint8 health_flags # Bitmask to indicate sensor health states (vel, pos, hgt) |
||||
uint8 timeout_flags # Bitmask to indicate timeout flags (vel, pos, hgt) |
@ -0,0 +1,4 @@
@@ -0,0 +1,4 @@
|
||||
uint8 GEOFENCE_MAX_VERTICES = 16 |
||||
|
||||
uint32 count # number of actual vertices |
||||
fence_vertex[16] vertices # geofence positions |
@ -0,0 +1,2 @@
@@ -0,0 +1,2 @@
|
||||
float32 lat # latitude in degrees, worst case float precision gives us 2 meter resolution at the equator |
||||
float32 lon # longitude in degrees, worst case float precision gives us 2 meter resolution at the equator |
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
bool geofence_violated # true if the geofence is violated |
@ -0,0 +1,3 @@
@@ -0,0 +1,3 @@
|
||||
uint64 timestamp # microseconds since system boot |
||||
float32 voltage_v # Servo rail voltage in volts |
||||
float32 rssi_v # RSSI pin voltage in volts |
@ -0,0 +1,22 @@
@@ -0,0 +1,22 @@
|
||||
uint64 SUBSYSTEM_TYPE_GYRO = 1 |
||||
uint64 SUBSYSTEM_TYPE_ACC = 2 |
||||
uint64 SUBSYSTEM_TYPE_MAG = 4 |
||||
uint64 SUBSYSTEM_TYPE_ABSPRESSURE = 8 |
||||
uint64 SUBSYSTEM_TYPE_DIFFPRESSURE = 16 |
||||
uint64 SUBSYSTEM_TYPE_GPS = 32 |
||||
uint64 SUBSYSTEM_TYPE_OPTICALFLOW = 64 |
||||
uint64 SUBSYSTEM_TYPE_CVPOSITION = 128 |
||||
uint64 SUBSYSTEM_TYPE_LASERPOSITION = 256 |
||||
uint64 SUBSYSTEM_TYPE_EXTERNALGROUNDTRUTH = 512 |
||||
uint64 SUBSYSTEM_TYPE_ANGULARRATECONTROL = 1024 |
||||
uint64 SUBSYSTEM_TYPE_ATTITUDESTABILIZATION = 2048 |
||||
uint64 SUBSYSTEM_TYPE_YAWPOSITION = 4096 |
||||
uint64 SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384 |
||||
uint64 SUBSYSTEM_TYPE_POSITIONCONTROL = 32768 |
||||
uint64 SUBSYSTEM_TYPE_MOTORCONTROL = 65536 |
||||
uint64 SUBSYSTEM_TYPE_RANGEFINDER = 131072 |
||||
|
||||
bool present |
||||
bool enabled |
||||
bool ok |
||||
uint64 subsystem_type |
@ -0,0 +1,7 @@
@@ -0,0 +1,7 @@
|
||||
uint64 timestamp # microseconds since system boot |
||||
float32 voltage5V_v # peripheral 5V rail voltage |
||||
uint8 usb_connected # USB is connected when 1 |
||||
uint8 brick_valid # brick power is good when 1 |
||||
uint8 servo_valid # servo power is good when 1 |
||||
uint8 periph_5V_OC # peripheral overcurrent when 1 |
||||
uint8 hipower_5V_OC # hi power peripheral overcurrent when 1 |
@ -0,0 +1,26 @@
@@ -0,0 +1,26 @@
|
||||
uint8 TECS_MODE_NORMAL = 0 |
||||
uint8 TECS_MODE_UNDERSPEED = 1 |
||||
uint8 TECS_MODE_TAKEOFF = 2 |
||||
uint8 TECS_MODE_LAND = 3 |
||||
uint8 TECS_MODE_LAND_THROTTLELIM = 4 |
||||
uint8 TECS_MODE_BAD_DESCENT = 5 |
||||
uint8 TECS_MODE_CLIMBOUT = 6 |
||||
|
||||
uint64 timestamp # timestamp, in microseconds since system start */ |
||||
|
||||
float32 altitudeSp |
||||
float32 altitude_filtered |
||||
float32 flightPathAngleSp |
||||
float32 flightPathAngle |
||||
float32 flightPathAngleFiltered |
||||
float32 airspeedSp |
||||
float32 airspeed_filtered |
||||
float32 airspeedDerivativeSp |
||||
float32 airspeedDerivative |
||||
|
||||
float32 totalEnergyRateSp |
||||
float32 totalEnergyRate |
||||
float32 energyDistributionRateSp |
||||
float32 energyDistributionRate |
||||
|
||||
uint8 mode |
@ -0,0 +1,5 @@
@@ -0,0 +1,5 @@
|
||||
uint8 NUM_MOTOR_OUTPUTS = 8 |
||||
|
||||
uint64 timestamp # output timestamp in us since system boot |
||||
uint32 motor_number # number of motor to spin |
||||
float32 value # output power, range [0..1] |
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
uint64 offset_ns # time offset between companion system and PX4, in nanoseconds |
@ -0,0 +1,81 @@
@@ -0,0 +1,81 @@
|
||||
|
||||
uint32 VEHICLE_CMD_CUSTOM_0 = 0 # test command |
||||
uint32 VEHICLE_CMD_CUSTOM_1 = 1 # test command |
||||
uint32 VEHICLE_CMD_CUSTOM_2 = 2 # test command |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_NAV_GUIDED_MASTER = 91 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 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| |
||||
uint32 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 VEHICLE_CMD_DO_FLIGHTTERMINATION=185 # Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 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| |
||||
uint32 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| |
||||
uint32 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| |
||||
uint32 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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| |
||||
uint32 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)| |
||||
uint32 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm| |
||||
uint32 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| |
||||
uint32 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan |
||||
uint32 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment |
||||
|
||||
uint32 VEHICLE_CMD_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED | |
||||
uint32 VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED | |
||||
uint32 VEHICLE_CMD_RESULT_DENIED = 2 # Command PERMANENTLY DENIED | |
||||
uint32 VEHICLE_CMD_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED | |
||||
uint32 VEHICLE_CMD_RESULT_FAILED = 4 # Command executed, but failed | |
||||
uint32 VEHICLE_CMD_RESULT_ENUM_END = 5 # |
||||
|
||||
uint32 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | |
||||
uint32 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | |
||||
uint32 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | |
||||
uint32 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | |
||||
uint32 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt | |
||||
uint32 VEHICLE_MOUNT_MODE_ENUM_END = 5 # |
||||
|
||||
float32 param1 # Parameter 1, as defined by MAVLink uint32 VEHICLE_CMD enum. |
||||
float32 param2 # Parameter 2, as defined by MAVLink uint32 VEHICLE_CMD enum. |
||||
float32 param3 # Parameter 3, as defined by MAVLink uint32 VEHICLE_CMD enum. |
||||
float32 param4 # Parameter 4, as defined by MAVLink uint32 VEHICLE_CMD enum. |
||||
float64 param5 # Parameter 5, as defined by MAVLink uint32 VEHICLE_CMD enum. |
||||
float64 param6 # Parameter 6, as defined by MAVLink uint32 VEHICLE_CMD enum. |
||||
float32 param7 # Parameter 7, as defined by MAVLink uint32 VEHICLE_CMD enum. |
||||
uint32 command # Command ID, as defined MAVLink by uint32 VEHICLE_CMD enum. |
||||
uint32 target_system # System which should execute the command |
||||
uint32 target_component # Component which should execute the command, 0 for all components |
||||
uint32 source_system # System sending the command |
||||
uint32 source_component # Component sending the command |
||||
uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) |
@ -0,0 +1,2 @@
@@ -0,0 +1,2 @@
|
||||
uint64 timestamp # timestamp of the setpoint |
||||
bool landed # true if vehicle is currently landed on the ground |
@ -0,0 +1,10 @@
@@ -0,0 +1,10 @@
|
||||
uint64 timestamp # time of this estimate, in microseconds since system start |
||||
bool valid # true if position satisfies validity criteria of estimator |
||||
|
||||
float32 x # X position in meters in NED earth-fixed frame |
||||
float32 y # Y position in meters in NED earth-fixed frame |
||||
float32 z # Z position in meters in NED earth-fixed frame (negative altitude) |
||||
float32 roll |
||||
float32 pitch |
||||
float32 yaw |
||||
float32[4] q # Attitude as quaternion |
@ -0,0 +1,14 @@
@@ -0,0 +1,14 @@
|
||||
uint32 id # ID of the estimator, commonly the component ID of the incoming message |
||||
|
||||
uint64 timestamp_boot # time of this estimate, in microseconds since system start |
||||
uint64 timestamp_computer # timestamp provided by the companion computer, in us |
||||
|
||||
float32 x # X position in meters in NED earth-fixed frame |
||||
float32 y # Y position in meters in NED earth-fixed frame |
||||
float32 z # Z position in meters in NED earth-fixed frame (negative altitude) |
||||
|
||||
float32 vx # X velocity in meters per second in NED earth-fixed frame |
||||
float32 vy # Y velocity in meters per second in NED earth-fixed frame |
||||
float32 vz # Z velocity in meters per second in NED earth-fixed frame |
||||
|
||||
float32[4] q # Estimated attitude as quaternion |
@ -0,0 +1,4 @@
@@ -0,0 +1,4 @@
|
||||
uint64 timestamp # Microseconds since system boot |
||||
bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode |
||||
bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode |
||||
float32 airspeed_tot # Estimated airspeed over control surfaces |
@ -0,0 +1,5 @@
@@ -0,0 +1,5 @@
|
||||
uint64 timestamp # Microseconds since system boot |
||||
float32 windspeed_north # Wind component in north / X direction |
||||
float32 windspeed_east # Wind component in east / Y direction |
||||
float32 covariance_north # Uncertainty - set to zero (no uncertainty) if not estimated |
||||
float32 covariance_east # Uncertainty - set to zero (no uncertainty) if not estimated |
@ -0,0 +1,131 @@
@@ -0,0 +1,131 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2015 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file px4io_params.c |
||||
* |
||||
* Parameters defined by the PX4IO driver |
||||
* |
||||
* @author Lorenz Meier <lorenz@px4.io> |
||||
*/ |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <systemlib/param/param.h> |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 1 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0); |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 2 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0); |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 3 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0); |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 4 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0); |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 5 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0); |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 6 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0); |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 7 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0); |
||||
|
||||
/**
|
||||
* Invert direction of main output channel 8 |
||||
* |
||||
* Set to 1 to invert the channel, 0 for default direction. |
||||
* |
||||
* @min 0 |
||||
* @max 1 |
||||
* @group PWM Outputs |
||||
*/ |
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0); |
@ -1,69 +0,0 @@
@@ -1,69 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file actuator_direct.h |
||||
* |
||||
* Actuator direct values. |
||||
* |
||||
* Values published to this topic are the direct actuator values which |
||||
* should be passed to actuators, bypassing mixing |
||||
*/ |
||||
|
||||
#ifndef TOPIC_ACTUATOR_DIRECT_H |
||||
#define TOPIC_ACTUATOR_DIRECT_H |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
#define NUM_ACTUATORS_DIRECT 16 |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
struct actuator_direct_s { |
||||
uint64_t timestamp; /**< timestamp in us since system boot */ |
||||
float values[NUM_ACTUATORS_DIRECT]; /**< actuator values, from -1 to 1 */ |
||||
unsigned nvalues; /**< number of valid values */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* actuator direct ORB */ |
||||
ORB_DECLARE(actuator_direct); |
||||
|
||||
#endif // TOPIC_ACTUATOR_DIRECT_H
|
@ -1,73 +0,0 @@
@@ -1,73 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file actuator_outputs.h |
||||
* |
||||
* Actuator output values. |
||||
* |
||||
* Values published to these topics are the outputs of the control mixing |
||||
* system as sent to the actuators (servos, motors, etc.) that operate |
||||
* the vehicle. |
||||
* |
||||
* Each topic can be published by a single output driver. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_ACTUATOR_OUTPUTS_H |
||||
#define TOPIC_ACTUATOR_OUTPUTS_H |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
#define NUM_ACTUATOR_OUTPUTS 16 |
||||
#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */ |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
struct actuator_outputs_s { |
||||
uint64_t timestamp; /**< output timestamp in us since system boot */ |
||||
float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */ |
||||
unsigned noutputs; /**< valid outputs */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* actuator output sets; this list can be expanded as more drivers emerge */ |
||||
ORB_DECLARE(actuator_outputs); |
||||
|
||||
#endif |
@ -1,68 +0,0 @@
@@ -1,68 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file airspeed.h |
||||
* |
||||
* Definition of airspeed topic |
||||
*/ |
||||
|
||||
#ifndef TOPIC_AIRSPEED_H_ |
||||
#define TOPIC_AIRSPEED_H_ |
||||
|
||||
#include <platforms/px4_defines.h> |
||||
#include <stdint.h> |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Airspeed |
||||
*/ |
||||
struct airspeed_s { |
||||
uint64_t timestamp; /**< microseconds since system boot, needed to integrate */ |
||||
float indicated_airspeed_m_s; /**< indicated airspeed in meters per second, -1 if unknown */ |
||||
float true_airspeed_m_s; /**< true airspeed in meters per second, -1 if unknown */ |
||||
float air_temperature_celsius; /**< air temperature in degrees celsius, -1000 if unknown */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(airspeed); |
||||
|
||||
#endif |
@ -1,69 +0,0 @@
@@ -1,69 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file battery_status.h |
||||
* |
||||
* Definition of the battery status uORB topic. |
||||
*/ |
||||
|
||||
#ifndef BATTERY_STATUS_H_ |
||||
#define BATTERY_STATUS_H_ |
||||
|
||||
#include "../uORB.h" |
||||
#include <stdint.h> |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Battery voltages and status |
||||
*/ |
||||
struct battery_status_s { |
||||
uint64_t timestamp; /**< microseconds since system boot, needed to integrate */ |
||||
float voltage_v; /**< Battery voltage in volts, 0 if unknown */ |
||||
float voltage_filtered_v; /**< Battery voltage in volts, filtered, 0 if unknown */ |
||||
float current_a; /**< Battery current in amperes, -1 if unknown */ |
||||
float discharged_mah; /**< Discharged amount in mAh, -1 if unknown */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(battery_status); |
||||
|
||||
#endif |
@ -1,76 +0,0 @@
@@ -1,76 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file debug_key_value.h |
||||
* Definition of the debug named value uORB topic. Allows to send a 10-char key |
||||
* with a float as value. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_DEBUG_KEY_VALUE_H_ |
||||
#define TOPIC_DEBUG_KEY_VALUE_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Key/value pair for debugging |
||||
*/ |
||||
struct debug_key_value_s { |
||||
|
||||
/*
|
||||
* Actual data, this is specific to the type of data which is stored in this struct |
||||
* A line containing L0GME will be added by the Python logging code generator to the |
||||
* logged dataset. |
||||
*/ |
||||
uint32_t timestamp_ms; /**< in milliseconds since system start */ |
||||
char key[10]; /**< max. 10 characters as key / name */ |
||||
float value; /**< the value to send as debug output */ |
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(debug_key_value); |
||||
|
||||
#endif |
@ -1,71 +0,0 @@
@@ -1,71 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file differential_pressure.h |
||||
* |
||||
* Definition of differential pressure topic |
||||
*/ |
||||
|
||||
#ifndef TOPIC_DIFFERENTIAL_PRESSURE_H_ |
||||
#define TOPIC_DIFFERENTIAL_PRESSURE_H_ |
||||
|
||||
#include "../uORB.h" |
||||
#include <stdint.h> |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Differential pressure. |
||||
*/ |
||||
struct differential_pressure_s { |
||||
uint64_t timestamp; /**< Microseconds since system boot, needed to integrate */ |
||||
uint64_t error_count; /**< Number of errors detected by driver */ |
||||
float differential_pressure_raw_pa; /**< Raw differential pressure reading (may be negative) */ |
||||
float differential_pressure_filtered_pa; /**< Low pass filtered differential pressure reading */ |
||||
float max_differential_pressure_pa; /**< Maximum differential pressure reading */ |
||||
float temperature; /**< Temperature provided by sensor, -1000.0f if unknown */ |
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(differential_pressure); |
||||
|
||||
#endif |
@ -1,66 +0,0 @@
@@ -1,66 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file encoders.h |
||||
* |
||||
* Encoders topic. |
||||
* |
||||
*/ |
||||
|
||||
#ifndef TOPIC_ENCODERS_H |
||||
#define TOPIC_ENCODERS_H |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
#define NUM_ENCODERS 4 |
||||
|
||||
struct encoders_s { |
||||
uint64_t timestamp; |
||||
int64_t counts[NUM_ENCODERS]; // counts of encoder
|
||||
float velocity[NUM_ENCODERS]; // counts of encoder/ second
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
ORB_DECLARE(encoders); |
||||
|
||||
#endif |
@ -1,116 +0,0 @@
@@ -1,116 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved. |
||||
* Author: @author Marco Bauer <marco@wtns.de> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file esc_status.h |
||||
* Definition of the esc_status uORB topic. |
||||
* |
||||
* Published the state machine and the system status bitfields |
||||
* (see SYS_STATUS mavlink message), published only by commander app. |
||||
* |
||||
* All apps should write to subsystem_info: |
||||
* |
||||
* (any app) --> subsystem_info (published) --> (commander app state machine) --> esc_status --> (mavlink app) |
||||
*/ |
||||
|
||||
#ifndef ESC_STATUS_H_ |
||||
#define ESC_STATUS_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* The number of ESCs supported. |
||||
* Current (Q2/2013) we support 8 ESCs, |
||||
*/ |
||||
#define CONNECTED_ESC_MAX 8 |
||||
|
||||
enum ESC_VENDOR { |
||||
ESC_VENDOR_GENERIC = 0, /**< generic ESC */ |
||||
ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */ |
||||
ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */ |
||||
}; |
||||
|
||||
enum ESC_CONNECTION_TYPE { |
||||
ESC_CONNECTION_TYPE_PPM = 0, /**< Traditional PPM ESC */ |
||||
ESC_CONNECTION_TYPE_SERIAL, /**< Serial Bus connected ESC */ |
||||
ESC_CONNECTION_TYPE_ONESHOOT, /**< One Shoot PPM */ |
||||
ESC_CONNECTION_TYPE_I2C, /**< I2C */ |
||||
ESC_CONNECTION_TYPE_CAN /**< CAN-Bus */ |
||||
}; |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Electronic speed controller status. |
||||
* Unsupported float fields should be assigned NaN. |
||||
*/ |
||||
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 { |
||||
enum ESC_VENDOR esc_vendor; /**< Vendor of current ESC */ |
||||
uint32_t esc_errorcount; /**< Number of reported errors by ESC - if supported */ |
||||
int32_t esc_rpm; /**< Motor RPM, negative for reverse rotation [RPM] - if supported */ |
||||
float esc_voltage; /**< Voltage measured from current ESC [V] - if supported */ |
||||
float esc_current; /**< Current measured from current ESC [A] - if supported */ |
||||
float esc_temperature; /**< Temperature measured from current ESC [degC] - if supported */ |
||||
float esc_setpoint; /**< setpoint of current ESC */ |
||||
uint16_t esc_setpoint_raw; /**< setpoint of current ESC (Value sent to ESC) */ |
||||
uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */ |
||||
uint16_t esc_version; /**< Version of current ESC - if supported */ |
||||
uint16_t esc_state; /**< State of ESC - depend on Vendor */ |
||||
} esc[CONNECTED_ESC_MAX]; |
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
//ORB_DECLARE(esc_status);
|
||||
ORB_DECLARE_OPTIONAL(esc_status); |
||||
|
||||
#endif |
@ -1,80 +0,0 @@
@@ -1,80 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file estimator_status.h |
||||
* Definition of the estimator_status_report uORB topic. |
||||
* |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
*/ |
||||
|
||||
#ifndef ESTIMATOR_STATUS_H_ |
||||
#define ESTIMATOR_STATUS_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Estimator status report. |
||||
* |
||||
* This is a generic status report struct which allows any of the onboard estimators |
||||
* to write the internal state to the system log. |
||||
* |
||||
*/ |
||||
struct estimator_status_report { |
||||
|
||||
/* NOTE: Ordering of fields optimized to align to 32 bit / 4 bytes - change with consideration only */ |
||||
|
||||
uint64_t timestamp; /**< Timestamp in microseconds since boot */ |
||||
float states[32]; /**< Internal filter states */ |
||||
float n_states; /**< Number of states effectively used */ |
||||
uint8_t nan_flags; /**< Bitmask to indicate NaN states */ |
||||
uint8_t health_flags; /**< Bitmask to indicate sensor health states (vel, pos, hgt) */ |
||||
uint8_t timeout_flags; /**< Bitmask to indicate timeout flags (vel, pos, hgt) */ |
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(estimator_status); |
||||
|
||||
#endif |
@ -1,80 +0,0 @@
@@ -1,80 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: @author Jean Cyr <jean.m.cyr@gmail.com> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file fence.h |
||||
* Definition of geofence. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_FENCE_H_ |
||||
#define TOPIC_FENCE_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include <platforms/px4_defines.h> |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
#define GEOFENCE_MAX_VERTICES 16 |
||||
|
||||
/**
|
||||
* This is the position of a geofence vertex |
||||
* |
||||
*/ |
||||
struct fence_vertex_s { |
||||
// Worst case float precision gives us 2 meter resolution at the equator
|
||||
float lat; /**< latitude in degrees */ |
||||
float lon; /**< longitude in degrees */ |
||||
}; |
||||
|
||||
/**
|
||||
* This is the position of a geofence |
||||
* |
||||
*/ |
||||
struct fence_s { |
||||
unsigned count; /**< number of actual vertices */ |
||||
struct fence_vertex_s vertices[GEOFENCE_MAX_VERTICES]; |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(fence); |
||||
|
||||
#endif |
@ -1,64 +0,0 @@
@@ -1,64 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2014 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file geofence_result.h |
||||
* Status of the plance concerning the geofence |
||||
* |
||||
* @author Ban Siesta <bansiesta@gmail.com> |
||||
*/ |
||||
|
||||
#ifndef TOPIC_GEOFENCE_RESULT_H |
||||
#define TOPIC_GEOFENCE_RESULT_H |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
struct geofence_result_s { |
||||
bool geofence_violated; /**< true if the geofence is violated */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(geofence_result); |
||||
|
||||
#endif |
@ -1,76 +0,0 @@
@@ -1,76 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file optical_flow.h |
||||
* Definition of the optical flow uORB topic. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_OMNIDIRECTIONAL_FLOW_H_ |
||||
#define TOPIC_OMNIDIRECTIONAL_FLOW_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Omnidirectional optical flow in NED body frame in SI units. |
||||
* |
||||
* @see http://en.wikipedia.org/wiki/International_System_of_Units
|
||||
*/ |
||||
struct omnidirectional_flow_s { |
||||
|
||||
uint64_t timestamp; /**< in microseconds since system start */ |
||||
|
||||
uint16_t left[10]; /**< Left flow, in decipixels */ |
||||
uint16_t right[10]; /**< Right flow, in decipixels */ |
||||
float front_distance_m; /**< Altitude / distance to object front in meters */ |
||||
uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */ |
||||
uint8_t sensor_id; /**< id of the sensor emitting the flow value */ |
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(omnidirectional_flow); |
||||
|
||||
#endif |
@ -1,67 +0,0 @@
@@ -1,67 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file servorail_status.h |
||||
* |
||||
* Definition of the servorail status uORB topic. |
||||
*/ |
||||
|
||||
#ifndef SERVORAIL_STATUS_H_ |
||||
#define SERVORAIL_STATUS_H_ |
||||
|
||||
#include "../uORB.h" |
||||
#include <stdint.h> |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Servorail voltages and status |
||||
*/ |
||||
struct servorail_status_s { |
||||
uint64_t timestamp; /**< microseconds since system boot */ |
||||
float voltage_v; /**< Servo rail voltage in volts */ |
||||
float rssi_v; /**< RSSI pin voltage in volts */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(servorail_status); |
||||
|
||||
#endif |
@ -1,96 +0,0 @@
@@ -1,96 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: Lorenz Meier <lm@inf.ethz.ch> |
||||
* Thomas Gubler <thomasgubler@student.ethz.ch> |
||||
* Julian Oes <joes@student.ethz.ch> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file subsystem_info.h |
||||
* Definition of the subsystem info topic. |
||||
* |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch> |
||||
* @author Julian Oes <joes@student.ethz.ch> |
||||
*/ |
||||
|
||||
#ifndef TOPIC_SUBSYSTEM_INFO_H_ |
||||
#define TOPIC_SUBSYSTEM_INFO_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
enum SUBSYSTEM_TYPE { |
||||
SUBSYSTEM_TYPE_GYRO = 1, |
||||
SUBSYSTEM_TYPE_ACC = 2, |
||||
SUBSYSTEM_TYPE_MAG = 4, |
||||
SUBSYSTEM_TYPE_ABSPRESSURE = 8, |
||||
SUBSYSTEM_TYPE_DIFFPRESSURE = 16, |
||||
SUBSYSTEM_TYPE_GPS = 32, |
||||
SUBSYSTEM_TYPE_OPTICALFLOW = 64, |
||||
SUBSYSTEM_TYPE_CVPOSITION = 128, |
||||
SUBSYSTEM_TYPE_LASERPOSITION = 256, |
||||
SUBSYSTEM_TYPE_EXTERNALGROUNDTRUTH = 512, |
||||
SUBSYSTEM_TYPE_ANGULARRATECONTROL = 1024, |
||||
SUBSYSTEM_TYPE_ATTITUDESTABILIZATION = 2048, |
||||
SUBSYSTEM_TYPE_YAWPOSITION = 4096, |
||||
SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384, |
||||
SUBSYSTEM_TYPE_POSITIONCONTROL = 32768, |
||||
SUBSYSTEM_TYPE_MOTORCONTROL = 65536, |
||||
SUBSYSTEM_TYPE_RANGEFINDER = 131072 |
||||
}; |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
*/ |
||||
|
||||
/**
|
||||
* State of individual sub systems |
||||
*/ |
||||
struct subsystem_info_s { |
||||
bool present; |
||||
bool enabled; |
||||
bool ok; |
||||
|
||||
enum SUBSYSTEM_TYPE subsystem_type; |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(subsystem_info); |
||||
|
||||
#endif /* TOPIC_SUBSYSTEM_INFO_H_ */ |
||||
|
@ -1,71 +0,0 @@
@@ -1,71 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file system_power.h |
||||
* |
||||
* Definition of the system_power voltage and power status uORB topic. |
||||
*/ |
||||
|
||||
#ifndef SYSTEM_POWER_H_ |
||||
#define SYSTEM_POWER_H_ |
||||
|
||||
#include "../uORB.h" |
||||
#include <stdint.h> |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* voltage and power supply status |
||||
*/ |
||||
struct system_power_s { |
||||
uint64_t timestamp; /**< microseconds since system boot */ |
||||
float voltage5V_v; /**< peripheral 5V rail voltage */ |
||||
uint8_t usb_connected:1; /**< USB is connected when 1 */ |
||||
uint8_t brick_valid:1; /**< brick power is good when 1 */ |
||||
uint8_t servo_valid:1; /**< servo power is good when 1 */ |
||||
uint8_t periph_5V_OC:1; /**< peripheral overcurrent when 1 */ |
||||
uint8_t hipower_5V_OC:1; /**< hi power peripheral overcurrent when 1 */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(system_power); |
||||
|
||||
#endif |
@ -1,94 +0,0 @@
@@ -1,94 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vehicle_global_position.h |
||||
* Definition of the global fused WGS84 position uORB topic. |
||||
* |
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch> |
||||
*/ |
||||
|
||||
#ifndef TECS_STATUS_T_H_ |
||||
#define TECS_STATUS_T_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
typedef enum { |
||||
TECS_MODE_NORMAL = 0, |
||||
TECS_MODE_UNDERSPEED, |
||||
TECS_MODE_TAKEOFF, |
||||
TECS_MODE_LAND, |
||||
TECS_MODE_LAND_THROTTLELIM, |
||||
TECS_MODE_BAD_DESCENT, |
||||
TECS_MODE_CLIMBOUT |
||||
} tecs_mode; |
||||
|
||||
/**
|
||||
* Internal values of the (m)TECS fixed wing speed alnd altitude control system |
||||
*/ |
||||
struct tecs_status_s { |
||||
uint64_t timestamp; /**< timestamp, in microseconds since system start */ |
||||
|
||||
float altitudeSp; |
||||
float altitude_filtered; |
||||
float flightPathAngleSp; |
||||
float flightPathAngle; |
||||
float flightPathAngleFiltered; |
||||
float airspeedSp; |
||||
float airspeed_filtered; |
||||
float airspeedDerivativeSp; |
||||
float airspeedDerivative; |
||||
|
||||
float totalEnergyRateSp; |
||||
float totalEnergyRate; |
||||
float energyDistributionRateSp; |
||||
float energyDistributionRate; |
||||
|
||||
tecs_mode mode; |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(tecs_status); |
||||
|
||||
#endif |
@ -1,70 +0,0 @@
@@ -1,70 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2014 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file test_motor.h |
||||
* |
||||
* Test a single drive motor while the vehicle is disarmed |
||||
* |
||||
* Publishing values to this topic causes a single motor to spin, e.g. for |
||||
* ground test purposes. This topic will be ignored while the vehicle is armed. |
||||
* |
||||
*/ |
||||
|
||||
#ifndef TOPIC_TEST_MOTOR_H |
||||
#define TOPIC_TEST_MOTOR_H |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
#define NUM_MOTOR_OUTPUTS 8 |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
struct test_motor_s { |
||||
uint64_t timestamp; /**< output timestamp in us since system boot */ |
||||
unsigned motor_number; /**< number of motor to spin */ |
||||
float value; /**< output power, range [0..1] */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* actuator output sets; this list can be expanded as more drivers emerge */ |
||||
ORB_DECLARE(test_motor); |
||||
|
||||
#endif |
@ -1,68 +0,0 @@
@@ -1,68 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. |
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch> |
||||
* Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vehicle_bodyframe_speed_setpoint.h |
||||
* Definition of the bodyframe speed setpoint uORB topic. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_VEHICLE_BODYFRAME_SPEED_SETPOINT_H_ |
||||
#define TOPIC_VEHICLE_BODYFRAME_SPEED_SETPOINT_H_ |
||||
|
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
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 */ |
||||
float vy; /**< in m/s */ |
||||
// float vz; /**< in m/s */
|
||||
float thrust_sp; |
||||
float yaw_sp; /**< in radian -PI +PI */ |
||||
}; /**< Speed in bodyframe to go to */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vehicle_bodyframe_speed_setpoint); |
||||
|
||||
#endif |
@ -1,172 +0,0 @@
@@ -1,172 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2014 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vehicle_command.h |
||||
* Definition of the vehicle command uORB topic. |
||||
* |
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch> |
||||
* @author Julian Oes <joes@student.ethz.ch> |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* @author Anton Matosov <anton.matosov@gmail.com> |
||||
*/ |
||||
|
||||
#ifndef TOPIC_VEHICLE_COMMAND_H_ |
||||
#define TOPIC_VEHICLE_COMMAND_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* Commands for commander app. |
||||
* |
||||
* Should contain all commands from MAVLink's VEHICLE_CMD ENUM, |
||||
* but can contain additional ones. |
||||
*/ |
||||
enum VEHICLE_CMD { |
||||
VEHICLE_CMD_CUSTOM_0 = 0, /* test command */ |
||||
VEHICLE_CMD_CUSTOM_1 = 1, /* test command */ |
||||
VEHICLE_CMD_CUSTOM_2 = 2, /* test command */ |
||||
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_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_NAV_GUIDED_MASTER=91, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ |
||||
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_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| 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_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ |
||||
VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ |
||||
VEHICLE_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| 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_PAYLOAD_PREPARE_DEPLOY = 30001, /**< Prepare a payload deployment in the flight plan */ |
||||
VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 /**< Control a pre-programmed payload deployment */ |
||||
}; |
||||
|
||||
/**
|
||||
* Commands for commander app. |
||||
* |
||||
* Should contain all of MAVLink's MAV_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, /* | */ |
||||
}; |
||||
|
||||
/**
|
||||
* Commands for gimbal app. |
||||
* |
||||
* Should contain all of MAVLink's MAV_MOUNT_MODE values |
||||
* but can contain additional ones. |
||||
*/ |
||||
typedef enum VEHICLE_MOUNT_MODE |
||||
{ |
||||
VEHICLE_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */ |
||||
VEHICLE_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */ |
||||
VEHICLE_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ |
||||
VEHICLE_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ |
||||
VEHICLE_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ |
||||
VEHICLE_MOUNT_MODE_ENUM_END=5, /* | */ |
||||
} VEHICLE_MOUNT_MODE; |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
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. */ |
||||
float param4; /**< Parameter 4, as defined by MAVLink VEHICLE_CMD enum. */ |
||||
double param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */ |
||||
double param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */ |
||||
float param7; /**< Parameter 7, as defined by MAVLink VEHICLE_CMD enum. */ |
||||
enum VEHICLE_CMD command; /**< Command ID, as defined MAVLink by VEHICLE_CMD enum. */ |
||||
uint8_t target_system; /**< System which should execute the command */ |
||||
uint8_t target_component; /**< Component which should execute the command, 0 for all components */ |
||||
uint8_t source_system; /**< System sending the command */ |
||||
uint8_t source_component; /**< Component sending the command */ |
||||
uint8_t confirmation; /**< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) */ |
||||
}; /**< command sent to vehicle */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vehicle_command); |
||||
|
||||
|
||||
|
||||
#endif |
@ -1,86 +0,0 @@
@@ -1,86 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vehicle_control_debug.h |
||||
* For debugging purposes to log PID parts of controller |
||||
*/ |
||||
|
||||
#ifndef TOPIC_VEHICLE_CONTROL_DEBUG_H_ |
||||
#define TOPIC_VEHICLE_CONTROL_DEBUG_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
struct vehicle_control_debug_s { |
||||
uint64_t timestamp; /**< in microseconds since system start */ |
||||
|
||||
float roll_p; /**< roll P control part */ |
||||
float roll_i; /**< roll I control part */ |
||||
float roll_d; /**< roll D control part */ |
||||
|
||||
float roll_rate_p; /**< roll rate P control part */ |
||||
float roll_rate_i; /**< roll rate I control part */ |
||||
float roll_rate_d; /**< roll rate D control part */ |
||||
|
||||
float pitch_p; /**< pitch P control part */ |
||||
float pitch_i; /**< pitch I control part */ |
||||
float pitch_d; /**< pitch D control part */ |
||||
|
||||
float pitch_rate_p; /**< pitch rate P control part */ |
||||
float pitch_rate_i; /**< pitch rate I control part */ |
||||
float pitch_rate_d; /**< pitch rate D control part */ |
||||
|
||||
float yaw_p; /**< yaw P control part */ |
||||
float yaw_i; /**< yaw I control part */ |
||||
float yaw_d; /**< yaw D control part */ |
||||
|
||||
float yaw_rate_p; /**< yaw rate P control part */ |
||||
float yaw_rate_i; /**< yaw rate I control part */ |
||||
float yaw_rate_d; /**< yaw rate D control part */ |
||||
|
||||
}; /**< vehicle_control_debug */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vehicle_control_debug); |
||||
|
||||
#endif |
@ -1,63 +0,0 @@
@@ -1,63 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vehicle_land_detected.h |
||||
* Land detected uORB topic |
||||
* |
||||
* @author Johan Jansen <jnsn.johan@gmail.com> |
||||
*/ |
||||
|
||||
#ifndef __TOPIC_VEHICLE_LANDED_H__ |
||||
#define __TOPIC_VEHICLE_LANDED_H__ |
||||
|
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
struct vehicle_land_detected_s { |
||||
uint64_t timestamp; /**< timestamp of the setpoint */ |
||||
bool landed; /**< true if vehicle is currently landed on the ground*/ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vehicle_land_detected); |
||||
|
||||
#endif //__TOPIC_VEHICLE_LANDED_H__
|
@ -1,77 +0,0 @@
@@ -1,77 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vehicle_vicon_position.h |
||||
* Definition of the raw VICON Motion Capture position |
||||
*/ |
||||
|
||||
#ifndef TOPIC_VEHICLE_VICON_POSITION_H_ |
||||
#define TOPIC_VEHICLE_VICON_POSITION_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Fused local position in NED. |
||||
*/ |
||||
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 */ |
||||
|
||||
float x; /**< X positin in meters in NED earth-fixed frame */ |
||||
float y; /**< X positin in meters in NED earth-fixed frame */ |
||||
float z; /**< Z positin in meters in NED earth-fixed frame (negative altitude) */ |
||||
float roll; |
||||
float pitch; |
||||
float yaw; |
||||
|
||||
// TODO Add covariances here
|
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vehicle_vicon_position); |
||||
|
||||
#endif |
@ -1,82 +0,0 @@
@@ -1,82 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vision_position_estimate.h |
||||
* Vision based position estimate |
||||
*/ |
||||
|
||||
#ifndef TOPIC_VISION_POSITION_ESTIMATE_H_ |
||||
#define TOPIC_VISION_POSITION_ESTIMATE_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Vision based position estimate in NED frame |
||||
*/ |
||||
struct vision_position_estimate { |
||||
|
||||
unsigned id; /**< ID of the estimator, commonly the component ID of the incoming message */ |
||||
|
||||
uint64_t timestamp_boot; /**< time of this estimate, in microseconds since system start */ |
||||
uint64_t timestamp_computer; /**< timestamp provided by the companion computer, in us */ |
||||
|
||||
float x; /**< X position in meters in NED earth-fixed frame */ |
||||
float y; /**< Y position in meters in NED earth-fixed frame */ |
||||
float z; /**< Z position in meters in NED earth-fixed frame (negative altitude) */ |
||||
|
||||
float vx; /**< X velocity in meters per second in NED earth-fixed frame */ |
||||
float vy; /**< Y velocity in meters per second in NED earth-fixed frame */ |
||||
float vz; /**< Z velocity in meters per second in NED earth-fixed frame */ |
||||
|
||||
float q[4]; /**< Estimated attitude as quaternion */ |
||||
|
||||
// XXX Add covariances here
|
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vision_position_estimate); |
||||
|
||||
#endif /* TOPIC_VISION_POSITION_ESTIMATE_H_ */ |
@ -1,68 +0,0 @@
@@ -1,68 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file vtol_status.h |
||||
* |
||||
* Vtol status topic |
||||
* |
||||
*/ |
||||
|
||||
#ifndef TOPIC_VTOL_STATUS_H |
||||
#define TOPIC_VTOL_STATUS_H |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/* Indicates in which mode the vtol aircraft is in */ |
||||
struct vtol_vehicle_status_s { |
||||
|
||||
uint64_t timestamp; /**< Microseconds since system boot */ |
||||
bool vtol_in_rw_mode; /*true: vtol vehicle is in rotating wing mode */ |
||||
bool fw_permanent_stab; /**< In fw mode stabilize attitude even if in manual mode*/ |
||||
float airspeed_tot; /*< Estimated airspeed over control surfaces */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vtol_vehicle_status); |
||||
|
||||
#endif |
@ -1,68 +0,0 @@
@@ -1,68 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file wind_estimate.h |
||||
* |
||||
* Wind estimate topic topic |
||||
* |
||||
*/ |
||||
|
||||
#ifndef TOPIC_WIND_ESTIMATE_H |
||||
#define TOPIC_WIND_ESTIMATE_H |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/** Wind estimate */ |
||||
struct wind_estimate_s { |
||||
|
||||
uint64_t timestamp; /**< Microseconds since system boot */ |
||||
float windspeed_north; /**< Wind component in north / X direction */ |
||||
float windspeed_east; /**< Wind component in east / Y direction */ |
||||
float covariance_north; /**< Uncertainty - set to zero (no uncertainty) if not estimated */ |
||||
float covariance_east; /**< Uncertainty - set to zero (no uncertainty) if not estimated */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
ORB_DECLARE(wind_estimate); |
||||
|
||||
#endif |
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in new issue