Browse Source

Merge branch 'release_v1.0.0' of github.com:PX4/Firmware into beta

sbg
Lorenz Meier 10 years ago
parent
commit
12933fd382
  1. 2
      ROMFS/px4fmu_common/init.d/rc.mc_apps
  2. 7
      makefiles/config_px4fmu-v1_default.mk
  3. 4
      msg/actuator_direct.msg
  4. 5
      msg/actuator_outputs.msg
  5. 4
      msg/airspeed.msg
  6. 5
      msg/battery_status.msg
  7. 3
      msg/debug_key_value.msg
  8. 6
      msg/differential_pressure.msg
  9. 5
      msg/encoders.msg
  10. 11
      msg/esc_report.msg
  11. 19
      msg/esc_status.msg
  12. 6
      msg/estimator_status.msg
  13. 4
      msg/fence.msg
  14. 2
      msg/fence_vertex.msg
  15. 1
      msg/geofence_result.msg
  16. 3
      msg/servorail_status.msg
  17. 22
      msg/subsystem_info.msg
  18. 7
      msg/system_power.msg
  19. 26
      msg/tecs_status.msg
  20. 4
      msg/templates/uorb/msg.h.template
  21. 5
      msg/test_motor.msg
  22. 1
      msg/time_offset.msg
  23. 81
      msg/vehicle_command.msg
  24. 2
      msg/vehicle_land_detected.msg
  25. 11
      msg/vehicle_status.msg
  26. 10
      msg/vehicle_vicon_position.msg
  27. 14
      msg/vision_position_estimate.msg
  28. 4
      msg/vtol_vehicle_status.msg
  29. 5
      msg/wind_estimate.msg
  30. 2
      src/drivers/airspeed/airspeed.cpp
  31. 5
      src/drivers/drv_rc_input.h
  32. 14
      src/drivers/gimbal/gimbal.cpp
  33. 11
      src/drivers/gps/gps.cpp
  34. 4
      src/drivers/hott/messages.cpp
  35. 2
      src/drivers/ll40ls/ll40ls.cpp
  36. 2
      src/drivers/mb12xx/mb12xx.cpp
  37. 4
      src/drivers/mkblctrl/mkblctrl.cpp
  38. 4
      src/drivers/px4flow/px4flow.cpp
  39. 43
      src/drivers/px4fmu/fmu.cpp
  40. 3
      src/drivers/px4fmu/module.mk
  41. 80
      src/drivers/px4fmu/px4fmu_params.c
  42. 3
      src/drivers/px4io/module.mk
  43. 39
      src/drivers/px4io/px4io.cpp
  44. 131
      src/drivers/px4io/px4io_params.c
  45. 2
      src/drivers/trone/trone.cpp
  46. 7
      src/lib/conversion/rotation.cpp
  47. 6
      src/lib/conversion/rotation.h
  48. 2
      src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
  49. 26
      src/modules/bottle_drop/bottle_drop.cpp
  50. 12
      src/modules/commander/calibration_routines.cpp
  51. 163
      src/modules/commander/commander.cpp
  52. 14
      src/modules/commander/commander_params.c
  53. 2
      src/modules/commander/state_machine_helper.cpp
  54. 4
      src/modules/dataman/dataman.h
  55. 2
      src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
  56. 24
      src/modules/fw_att_control/fw_att_control_main.cpp
  57. 20
      src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
  58. 18
      src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
  59. 6
      src/modules/fw_pos_control_l1/mtecs/mTecs.h
  60. 28
      src/modules/land_detector/land_detector_main.cpp
  61. 9
      src/modules/mavlink/mavlink_main.cpp
  62. 18
      src/modules/mavlink/mavlink_main.h
  63. 103
      src/modules/mavlink/mavlink_receiver.cpp
  64. 4
      src/modules/navigator/geofence.cpp
  65. 6
      src/modules/navigator/mission_feasibility_checker.cpp
  66. 5
      src/modules/navigator/navigator_main.cpp
  67. 6
      src/modules/position_estimator_inav/position_estimator_inav_main.c
  68. 5
      src/modules/px4iofirmware/mixer.cpp
  69. 2
      src/modules/px4iofirmware/protocol.h
  70. 2
      src/modules/px4iofirmware/px4io.h
  71. 5
      src/modules/px4iofirmware/registers.c
  72. 4
      src/modules/sdlog2/sdlog2.c
  73. 21
      src/modules/systemlib/pwm_limit/pwm_limit.c
  74. 2
      src/modules/systemlib/pwm_limit/pwm_limit.h
  75. 13
      src/modules/uORB/objects_common.cpp
  76. 69
      src/modules/uORB/topics/actuator_direct.h
  77. 73
      src/modules/uORB/topics/actuator_outputs.h
  78. 68
      src/modules/uORB/topics/airspeed.h
  79. 69
      src/modules/uORB/topics/battery_status.h
  80. 76
      src/modules/uORB/topics/debug_key_value.h
  81. 71
      src/modules/uORB/topics/differential_pressure.h
  82. 66
      src/modules/uORB/topics/encoders.h
  83. 116
      src/modules/uORB/topics/esc_status.h
  84. 80
      src/modules/uORB/topics/estimator_status.h
  85. 80
      src/modules/uORB/topics/fence.h
  86. 64
      src/modules/uORB/topics/geofence_result.h
  87. 76
      src/modules/uORB/topics/omnidirectional_flow.h
  88. 67
      src/modules/uORB/topics/servorail_status.h
  89. 96
      src/modules/uORB/topics/subsystem_info.h
  90. 71
      src/modules/uORB/topics/system_power.h
  91. 94
      src/modules/uORB/topics/tecs_status.h
  92. 70
      src/modules/uORB/topics/test_motor.h
  93. 68
      src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
  94. 172
      src/modules/uORB/topics/vehicle_command.h
  95. 86
      src/modules/uORB/topics/vehicle_control_debug.h
  96. 63
      src/modules/uORB/topics/vehicle_land_detected.h
  97. 77
      src/modules/uORB/topics/vehicle_vicon_position.h
  98. 82
      src/modules/uORB/topics/vision_position_estimate.h
  99. 68
      src/modules/uORB/topics/vtol_vehicle_status.h
  100. 68
      src/modules/uORB/topics/wind_estimate.h
  101. Some files were not shown because too many files have changed in this diff Show More

2
ROMFS/px4fmu_common/init.d/rc.mc_apps

@ -13,6 +13,8 @@ then @@ -13,6 +13,8 @@ then
# and uses the older EKF filter. However users can
# enable the new quaternion based complimentary
# filter by setting EKF_ATT_ENABLED = 0.
# Note that on FMUv1, the EKF att estimator is not
# available and the Q estimator runs instead.
if param compare EKF_ATT_ENABLED 1
then
attitude_estimator_ekf start

7
makefiles/config_px4fmu-v1_default.mk

@ -67,11 +67,10 @@ MODULES += modules/land_detector @@ -67,11 +67,10 @@ MODULES += modules/land_detector
# Estimation modules (EKF / other filters)
#
# Too high RAM usage due to static allocations
# MODULES += modules/attitude_estimator_ekf
#MODULES += modules/attitude_estimator_ekf
MODULES += modules/ekf_att_pos_estimator
# Since attitude_estimator_ekf is disabled, this app won't be
# worthwhile on its own
# MODULES += modules/position_estimator_inav
MODULES += modules/attitude_estimator_q
MODULES += modules/position_estimator_inav
#
# Vehicle Control

4
msg/actuator_direct.msg

@ -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

5
msg/actuator_outputs.msg

@ -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

4
msg/airspeed.msg

@ -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

5
msg/battery_status.msg

@ -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

3
msg/debug_key_value.msg

@ -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

6
msg/differential_pressure.msg

@ -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

5
msg/encoders.msg

@ -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

11
msg/esc_report.msg

@ -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

19
msg/esc_status.msg

@ -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

6
msg/estimator_status.msg

@ -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)

4
msg/fence.msg

@ -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

2
msg/fence_vertex.msg

@ -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

1
msg/geofence_result.msg

@ -0,0 +1 @@ @@ -0,0 +1 @@
bool geofence_violated # true if the geofence is violated

3
msg/servorail_status.msg

@ -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

22
msg/subsystem_info.msg

@ -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

7
msg/system_power.msg

@ -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

26
msg/tecs_status.msg

@ -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

4
msg/templates/uorb/msg.h.template

@ -106,8 +106,10 @@ type_map = {'int8': 'int8_t', @@ -106,8 +106,10 @@ type_map = {'int8': 'int8_t',
'float32': 'float',
'float64': 'double',
'bool': 'bool',
'char': 'char',
'fence_vertex': 'fence_vertex',
'position_setpoint': 'position_setpoint'}
'position_setpoint': 'position_setpoint',
'esc_report': 'esc_report'}
# Function to print a standard ros type
def print_field_def(field):

5
msg/test_motor.msg

@ -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]

1
msg/time_offset.msg

@ -0,0 +1 @@ @@ -0,0 +1 @@
uint64 offset_ns # time offset between companion system and PX4, in nanoseconds

81
msg/vehicle_command.msg

@ -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)

2
msg/vehicle_land_detected.msg

@ -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

11
msg/vehicle_status.msg

@ -81,6 +81,10 @@ uint8 VEHICLE_BATTERY_WARNING_NONE = 0 # no battery low voltage warning acti @@ -81,6 +81,10 @@ uint8 VEHICLE_BATTERY_WARNING_NONE = 0 # no battery low voltage warning acti
uint8 VEHICLE_BATTERY_WARNING_LOW = 1 # warning of low voltage
uint8 VEHICLE_BATTERY_WARNING_CRITICAL = 2 # alerting of critical voltage
uint8 RC_IN_MODE_DEFAULT = 0
uint8 RC_IN_MODE_OFF = 1
uint8 RC_IN_MODE_GENERATED = 2
# state machine / state of vehicle.
# Encodes the complete system state and is set by the commander app.
uint16 counter # incremented by the writing thread everytime new data is stored
@ -94,8 +98,8 @@ bool failsafe # true if system is in failsafe state @@ -94,8 +98,8 @@ bool failsafe # true if system is in failsafe state
bool calibration_enabled # true if current calibrating parts of the system. Also sets the system to ARMING_STATE_INIT.
int32 system_type # system type, inspired by MAVLink's VEHICLE_TYPE enum
int32 system_id # system id, inspired by MAVLink's system ID field
int32 component_id # subsystem / component id, inspired by MAVLink's component ID field
uint32 system_id # system id, inspired by MAVLink's system ID field
uint32 component_id # subsystem / component id, inspired by MAVLink's component ID field
bool is_rotary_wing # True if system is in rotary wing configuration, so for a VTOL this is only true while flying as a multicopter
bool is_vtol # True if the system is VTOL capable
@ -121,7 +125,8 @@ bool rc_signal_found_once @@ -121,7 +125,8 @@ bool rc_signal_found_once
bool rc_signal_lost # true if RC reception lost
uint64 rc_signal_lost_timestamp # Time at which the RC reception was lost
bool rc_signal_lost_cmd # true if RC lost mode is commanded
bool rc_input_blocked # set if RC input should be ignored
bool rc_input_blocked # set if RC input should be ignored temporarily
uint8 rc_input_mode # set to 1 to disable the RC input, 2 to enable manual control to RC in mapping.
bool data_link_lost # datalink to GCS lost
bool data_link_lost_cmd # datalink to GCS lost mode commanded

10
msg/vehicle_vicon_position.msg

@ -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

14
msg/vision_position_estimate.msg

@ -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

4
msg/vtol_vehicle_status.msg

@ -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

5
msg/wind_estimate.msg

@ -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

2
src/drivers/airspeed/airspeed.cpp

@ -364,7 +364,7 @@ Airspeed::update_status() @@ -364,7 +364,7 @@ Airspeed::update_status()
true,
true,
_sensor_ok,
SUBSYSTEM_TYPE_DIFFPRESSURE
subsystem_info_s::SUBSYSTEM_TYPE_DIFFPRESSURE
};
if (_subsys_pub > 0) {

5
src/drivers/drv_rc_input.h

@ -99,7 +99,8 @@ enum RC_INPUT_SOURCE { @@ -99,7 +99,8 @@ enum RC_INPUT_SOURCE {
RC_INPUT_SOURCE_PX4IO_PPM,
RC_INPUT_SOURCE_PX4IO_SPEKTRUM,
RC_INPUT_SOURCE_PX4IO_SBUS,
RC_INPUT_SOURCE_PX4IO_ST24
RC_INPUT_SOURCE_PX4IO_ST24,
RC_INPUT_SOURCE_MAVLINK
};
/**
@ -118,7 +119,7 @@ struct rc_input_values { @@ -118,7 +119,7 @@ struct rc_input_values {
/** number of channels actually being seen */
uint32_t channel_count;
/** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 255: full reception */
/** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception */
int32_t rssi;
/**

14
src/drivers/gimbal/gimbal.cpp

@ -331,13 +331,13 @@ Gimbal::cycle() @@ -331,13 +331,13 @@ Gimbal::cycle()
orb_copy(ORB_ID(vehicle_command), _vehicle_command_sub, &cmd);
if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL
|| cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT) {
if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL
|| cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT) {
_control_cmd = cmd;
_control_cmd_set = true;
} else if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONFIGURE) {
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE) {
_config_cmd = cmd;
_config_cmd_set = true;
@ -358,10 +358,11 @@ Gimbal::cycle() @@ -358,10 +358,11 @@ Gimbal::cycle()
if (_control_cmd_set) {
VEHICLE_MOUNT_MODE mountMode = (VEHICLE_MOUNT_MODE)_control_cmd.param7;
unsigned mountMode = _control_cmd.param7;
debug("control_cmd: %d, mountMode %d | param1: %8.4f param2: %8.4f", _control_cmd.command, mountMode, (double)_control_cmd.param1, (double)_control_cmd.param2);
if (_control_cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
if (_control_cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL &&
mountMode == vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
/* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */
roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param1;
pitch += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param2;
@ -370,7 +371,8 @@ Gimbal::cycle() @@ -370,7 +371,8 @@ Gimbal::cycle()
updated = true;
}
if (_control_cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
if (_control_cmd.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT &&
mountMode == vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
float gimbalDirectionQuat[] = {_control_cmd.param1, _control_cmd.param2, _control_cmd.param3, _control_cmd.param4};
math::Vector<3> gimablDirectionEuler = math::Quaternion(gimbalDirectionQuat).to_dcm().to_euler();

11
src/drivers/gps/gps.cpp

@ -361,11 +361,14 @@ GPS::task_main() @@ -361,11 +361,14 @@ GPS::task_main()
_report_gps_pos.timestamp_variance = hrt_absolute_time();
_report_gps_pos.timestamp_velocity = hrt_absolute_time();
_report_gps_pos.timestamp_time = hrt_absolute_time();
if (_report_gps_pos_pub > 0) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
if (!(_pub_blocked)) {
if (_report_gps_pos_pub > 0) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
}
// GPS is obviously detected successfully, reset statistics

4
src/drivers/hott/messages.cpp

@ -111,9 +111,9 @@ publish_gam_message(const uint8_t *buffer) @@ -111,9 +111,9 @@ publish_gam_message(const uint8_t *buffer)
// Publish it.
esc.timestamp = hrt_absolute_time();
esc.esc_count = 1;
esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
esc.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_PPM;
esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
esc.esc[0].esc_vendor = esc_status_s::ESC_VENDOR_GRAUPNER_HOTT;
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
esc.esc[0].esc_temperature = static_cast<float>(msg.temperature1) - 20.0F;
esc.esc[0].esc_voltage = static_cast<float>((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)) * 0.1F;

2
src/drivers/ll40ls/ll40ls.cpp

@ -734,7 +734,7 @@ LL40LS::start() @@ -734,7 +734,7 @@ LL40LS::start()
true,
true,
true,
SUBSYSTEM_TYPE_RANGEFINDER
subsystem_info_s::SUBSYSTEM_TYPE_RANGEFINDER
};
static orb_advert_t pub = -1;

2
src/drivers/mb12xx/mb12xx.cpp

@ -647,7 +647,7 @@ MB12XX::start() @@ -647,7 +647,7 @@ MB12XX::start()
true,
true,
true,
SUBSYSTEM_TYPE_RANGEFINDER
subsystem_info_s::SUBSYSTEM_TYPE_RANGEFINDER
};
static orb_advert_t pub = -1;

4
src/drivers/mkblctrl/mkblctrl.cpp

@ -601,11 +601,11 @@ MK::task_main() @@ -601,11 +601,11 @@ MK::task_main()
esc.counter++;
esc.timestamp = hrt_absolute_time();
esc.esc_count = (uint8_t) _num_outputs;
esc.esc_connectiontype = ESC_CONNECTION_TYPE_I2C;
esc.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_I2C;
for (unsigned int i = 0; i < _num_outputs; i++) {
esc.esc[i].esc_address = (uint8_t) BLCTRL_BASE_ADDR + i;
esc.esc[i].esc_vendor = ESC_VENDOR_MIKROKOPTER;
esc.esc[i].esc_vendor = esc_status_s::ESC_VENDOR_MIKROKOPTER;
esc.esc[i].esc_version = (uint16_t) Motor[i].Version;
esc.esc[i].esc_voltage = 0.0F;
esc.esc[i].esc_current = static_cast<float>(Motor[i].Current) * 0.1F;

4
src/drivers/px4flow/px4flow.cpp

@ -528,7 +528,7 @@ PX4FLOW::start() @@ -528,7 +528,7 @@ PX4FLOW::start()
true,
true,
true,
SUBSYSTEM_TYPE_OPTICALFLOW
subsystem_info_s::SUBSYSTEM_TYPE_OPTICALFLOW
};
static orb_advert_t pub = -1;
@ -674,7 +674,7 @@ fail: @@ -674,7 +674,7 @@ fail:
g_dev = nullptr;
}
errx(1, "no PX4 FLOW connected");
errx(1, "no PX4FLOW connected over I2C");
}
/**

43
src/drivers/px4fmu/fmu.cpp

@ -67,6 +67,7 @@ @@ -67,6 +67,7 @@
#include <systemlib/mixer/mixer.h>
#include <systemlib/pwm_limit/pwm_limit.h>
#include <systemlib/board_serial.h>
#include <systemlib/param/param.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_rc_input.h>
@ -77,6 +78,7 @@ @@ -77,6 +78,7 @@
#include <uORB/topics/actuator_controls_3.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_update.h>
#ifdef HRT_PPM_CHANNEL
@ -132,6 +134,7 @@ private: @@ -132,6 +134,7 @@ private:
unsigned _current_update_rate;
int _task;
int _armed_sub;
int _param_sub;
orb_advert_t _outputs_pub;
actuator_armed_s _armed;
unsigned _num_outputs;
@ -157,6 +160,7 @@ private: @@ -157,6 +160,7 @@ private:
uint16_t _disarmed_pwm[_max_actuators];
uint16_t _min_pwm[_max_actuators];
uint16_t _max_pwm[_max_actuators];
uint16_t _reverse_pwm_mask;
unsigned _num_failsafe_set;
unsigned _num_disarmed_set;
@ -167,9 +171,10 @@ private: @@ -167,9 +171,10 @@ private:
uint8_t control_group,
uint8_t control_index,
float &input);
void subscribe();
void subscribe();
int set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_rate);
int pwm_ioctl(file *filp, int cmd, unsigned long arg);
void update_pwm_rev_mask();
struct GPIOConfig {
uint32_t input;
@ -253,6 +258,7 @@ PX4FMU::PX4FMU() : @@ -253,6 +258,7 @@ PX4FMU::PX4FMU() :
_current_update_rate(0),
_task(-1),
_armed_sub(-1),
_param_sub(-1),
_outputs_pub(-1),
_armed{},
_num_outputs(0),
@ -269,6 +275,7 @@ PX4FMU::PX4FMU() : @@ -269,6 +275,7 @@ PX4FMU::PX4FMU() :
_pwm_limit{},
_failsafe_pwm{0},
_disarmed_pwm{0},
_reverse_pwm_mask(0),
_num_failsafe_set(0),
_num_disarmed_set(0)
{
@ -543,6 +550,26 @@ PX4FMU::subscribe() @@ -543,6 +550,26 @@ PX4FMU::subscribe()
}
}
void
PX4FMU::update_pwm_rev_mask()
{
_reverse_pwm_mask = 0;
for (unsigned i = 0; i < _max_actuators; i++) {
char pname[16];
int32_t ival;
/* fill the channel reverse mask from parameters */
sprintf(pname, "PWM_AUX_REV%d", i + 1);
param_t param_h = param_find(pname);
if (param_h != PARAM_INVALID) {
param_get(param_h, &ival);
_reverse_pwm_mask |= ((int16_t)(ival != 0)) << i;
}
}
}
void
PX4FMU::task_main()
{
@ -550,6 +577,7 @@ PX4FMU::task_main() @@ -550,6 +577,7 @@ PX4FMU::task_main()
_current_update_rate = 0;
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
_param_sub = orb_subscribe(ORB_ID(parameter_update));
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@ -567,7 +595,7 @@ PX4FMU::task_main() @@ -567,7 +595,7 @@ PX4FMU::task_main()
/* initialize PWM limit lib */
pwm_limit_init(&_pwm_limit);
log("starting");
update_pwm_rev_mask();
/* loop until killed */
while (!_task_should_exit) {
@ -684,7 +712,7 @@ PX4FMU::task_main() @@ -684,7 +712,7 @@ PX4FMU::task_main()
uint16_t pwm_limited[num_outputs];
/* the PWM limit call takes care of out of band errors and constrains */
pwm_limit_calc(_servo_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
pwm_limit_calc(_servo_armed, num_outputs, _reverse_pwm_mask, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
/* output to the servos */
for (unsigned i = 0; i < num_outputs; i++) {
@ -723,6 +751,14 @@ PX4FMU::task_main() @@ -723,6 +751,14 @@ PX4FMU::task_main()
}
}
orb_check(_param_sub, &updated);
if (updated) {
parameter_update_s pupdate;
orb_copy(ORB_ID(parameter_update), _param_sub, &pupdate);
update_pwm_rev_mask();
}
#ifdef HRT_PPM_CHANNEL
// see if we have new PPM input data
@ -768,6 +804,7 @@ PX4FMU::task_main() @@ -768,6 +804,7 @@ PX4FMU::task_main()
}
}
::close(_armed_sub);
::close(_param_sub);
/* make sure servos are off */
up_pwm_servo_deinit();

3
src/drivers/px4fmu/module.mk

@ -3,7 +3,8 @@ @@ -3,7 +3,8 @@
#
MODULE_COMMAND = fmu
SRCS = fmu.cpp
SRCS = fmu.cpp \
px4fmu_params.c
MODULE_STACKSIZE = 1200

80
src/modules/uORB/topics/time_offset.h → src/drivers/px4fmu/px4fmu_params.c

@ -32,36 +32,78 @@ @@ -32,36 +32,78 @@
****************************************************************************/
/**
* @file time_offset.h
* Time synchronisation offset
* @file px4fmu_params.c
*
* Parameters defined by the PX4FMU driver
*
* @author Lorenz Meier <lorenz@px4.io>
*/
#ifndef TOPIC_TIME_OFFSET_H_
#define TOPIC_TIME_OFFSET_H_
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
#include <nuttx/config.h>
#include <systemlib/param/param.h>
/**
* @addtogroup topics
* @{
* Invert direction of aux 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_AUX_REV1, 0);
/**
* Timesync offset for synchronisation with companion computer, GCS, etc.
* Invert direction of aux output channel 2
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @min 0
* @max 1
* @group PWM Outputs
*/
struct time_offset_s {
uint64_t offset_ns; /**< time offset between companion system and PX4, in nanoseconds */
PARAM_DEFINE_INT32(PWM_AUX_REV2, 0);
};
/**
* Invert direction of aux 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_AUX_REV3, 0);
/**
* @}
* Invert direction of aux 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_AUX_REV4, 0);
/* register this as object request broker structure */
ORB_DECLARE(time_offset);
/**
* Invert direction of aux 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_AUX_REV5, 0);
#endif /* TOPIC_TIME_OFFSET_H_ */
/**
* Invert direction of aux 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_AUX_REV6, 0);

3
src/drivers/px4io/module.mk

@ -40,7 +40,8 @@ MODULE_COMMAND = px4io @@ -40,7 +40,8 @@ MODULE_COMMAND = px4io
SRCS = px4io.cpp \
px4io_uploader.cpp \
px4io_serial.cpp \
px4io_i2c.cpp
px4io_i2c.cpp \
px4io_params.c
# XXX prune to just get UART registers
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common

39
src/drivers/px4io/px4io.cpp

@ -281,6 +281,7 @@ private: @@ -281,6 +281,7 @@ private:
int _t_actuator_armed; ///< system armed control topic
int _t_vehicle_control_mode;///< vehicle control mode topic
int _t_param; ///< parameter update topic
bool _param_update_force; ///< force a parameter update
int _t_vehicle_command; ///< vehicle command topic
/* advertised topics */
@ -514,6 +515,7 @@ PX4IO::PX4IO(device::Device *interface) : @@ -514,6 +515,7 @@ PX4IO::PX4IO(device::Device *interface) :
_t_actuator_armed(-1),
_t_vehicle_control_mode(-1),
_t_param(-1),
_param_update_force(false),
_t_vehicle_command(-1),
_to_input_rc(0),
_to_outputs(0),
@ -766,7 +768,7 @@ PX4IO::init() @@ -766,7 +768,7 @@ PX4IO::init()
cmd.param5 = 0;
cmd.param6 = 0;
cmd.param7 = 0;
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
cmd.command = vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM;
/* ask to confirm command */
cmd.confirmation = 1;
@ -917,6 +919,8 @@ PX4IO::task_main() @@ -917,6 +919,8 @@ PX4IO::task_main()
fds[0].fd = _t_actuator_controls_0;
fds[0].events = POLLIN;
_param_update_force = true;
/* lock against the ioctl handler */
lock();
@ -1005,7 +1009,7 @@ PX4IO::task_main() @@ -1005,7 +1009,7 @@ PX4IO::task_main()
orb_copy(ORB_ID(vehicle_command), _t_vehicle_command, &cmd);
// Check for a DSM pairing command
if (((int)cmd.command == VEHICLE_CMD_START_RX_PAIR) && ((int)cmd.param1 == 0)) {
if (((int)cmd.command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR) && ((int)cmd.param1 == 0)) {
dsm_bind_ioctl((int)cmd.param2);
}
}
@ -1017,7 +1021,8 @@ PX4IO::task_main() @@ -1017,7 +1021,8 @@ PX4IO::task_main()
*/
orb_check(_t_param, &updated);
if (updated) {
if (updated || _param_update_force) {
_param_update_force = false;
parameter_update_s pupdate;
orb_copy(ORB_ID(parameter_update), _t_param, &pupdate);
@ -1089,6 +1094,26 @@ PX4IO::task_main() @@ -1089,6 +1094,26 @@ PX4IO::task_main()
param_get(param_find("RC_RSSI_PWM_MAX"), &_rssi_pwm_max);
param_get(param_find("RC_RSSI_PWM_MIN"), &_rssi_pwm_min);
/*
* Set invert mask for PWM outputs (does not apply to S.Bus)
*/
int16_t pwm_invert_mask = 0;
for (unsigned i = 0; i < _max_actuators; i++) {
char pname[16];
int32_t ival;
/* fill the channel reverse mask from parameters */
sprintf(pname, "PWM_MAIN_REV%d", i + 1);
param_t param_h = param_find(pname);
if (param_h != PARAM_INVALID) {
param_get(param_h, &ival);
pwm_invert_mask |= ((int16_t)(ival != 0)) << i;
}
}
(void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_REVERSE, pwm_invert_mask);
}
}
@ -2095,7 +2120,15 @@ PX4IO::print_status(bool extended_status) @@ -2095,7 +2120,15 @@ PX4IO::print_status(bool extended_status)
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_SERVOS, i));
uint16_t pwm_invert_mask = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_REVERSE);
printf("\n");
printf("reversed outputs: [");
for (unsigned i = 0; i < _max_actuators; i++) {
printf("%s", (pwm_invert_mask & (1 << i)) ? "x" : "_");
}
printf("]\n");
uint16_t raw_inputs = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT);
printf("%d raw R/C inputs", raw_inputs);

131
src/drivers/px4io/px4io_params.c

@ -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);

2
src/drivers/trone/trone.cpp

@ -612,7 +612,7 @@ TRONE::start() @@ -612,7 +612,7 @@ TRONE::start()
true,
true,
true,
SUBSYSTEM_TYPE_RANGEFINDER
subsystem_info_s::SUBSYSTEM_TYPE_RANGEFINDER
};
static orb_advert_t pub = -1;

7
src/lib/conversion/rotation.cpp

@ -41,7 +41,7 @@ @@ -41,7 +41,7 @@
#include "rotation.h"
__EXPORT void
get_rot_matrix(enum Rotation rot, math::Matrix<3,3> *rot_matrix)
get_rot_matrix(enum Rotation rot, math::Matrix<3, 3> *rot_matrix)
{
float roll = M_DEG_TO_RAD_F * (float)rot_lookup[rot].roll;
float pitch = M_DEG_TO_RAD_F * (float)rot_lookup[rot].pitch;
@ -199,5 +199,10 @@ rotate_3f(enum Rotation rot, float &x, float &y, float &z) @@ -199,5 +199,10 @@ rotate_3f(enum Rotation rot, float &x, float &y, float &z)
y = -y;
return;
}
case ROTATION_PITCH_90_YAW_180: {
tmp = x; x = z; z = tmp;
y = -y;
return;
}
}
}

6
src/lib/conversion/rotation.h

@ -76,6 +76,7 @@ enum Rotation { @@ -76,6 +76,7 @@ enum Rotation {
ROTATION_PITCH_270 = 25,
ROTATION_ROLL_270_YAW_270 = 26,
ROTATION_ROLL_180_PITCH_270 = 27,
ROTATION_PITCH_90_YAW_180 = 28,
ROTATION_MAX
};
@ -113,14 +114,15 @@ const rot_lookup_t rot_lookup[] = { @@ -113,14 +114,15 @@ const rot_lookup_t rot_lookup[] = {
{ 0, 90, 0 },
{ 0, 270, 0 },
{270, 0, 270 },
{180, 270, 0 }
{180, 270, 0 },
{ 0, 90, 180 }
};
/**
* Get the rotation matrix
*/
__EXPORT void
get_rot_matrix(enum Rotation rot, math::Matrix<3, 3> *rot_matrix);
get_rot_matrix(enum Rotation rot, math::Matrix<3,3> *rot_matrix);
/**

2
src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp

@ -290,7 +290,7 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[]) @@ -290,7 +290,7 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
math::Matrix<3, 3> R_decl;
R_decl.identity();
struct vision_position_estimate vision {};
struct vision_position_estimate_s vision {};
/* register the perf counter */
perf_counter_t ekf_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_ekf");

26
src/modules/bottle_drop/bottle_drop.cpp

@ -152,7 +152,7 @@ private: @@ -152,7 +152,7 @@ private:
void handle_command(struct vehicle_command_s *cmd);
void answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result);
void answer_command(struct vehicle_command_s *cmd, unsigned result);
/**
* Set the actuators
@ -725,7 +725,7 @@ void @@ -725,7 +725,7 @@ void
BottleDrop::handle_command(struct vehicle_command_s *cmd)
{
switch (cmd->command) {
case VEHICLE_CMD_CUSTOM_0:
case vehicle_command_s::VEHICLE_CMD_CUSTOM_0:
/*
* param1 and param2 set to 1: open and drop
* param1 set to 1: open
@ -746,10 +746,10 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd) @@ -746,10 +746,10 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd)
mavlink_log_critical(_mavlink_fd, "closing bay");
}
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
break;
case VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
case vehicle_command_s::VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
switch ((int)(cmd->param1 + 0.5f)) {
case 0:
@ -777,10 +777,10 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd) @@ -777,10 +777,10 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd)
mavlink_log_info(_mavlink_fd, "got target: %8.4f, %8.4f, %8.4f", (double)_target_position.lat,
(double)_target_position.lon, (double)_target_position.alt);
map_projection_init(&ref, _target_position.lat, _target_position.lon);
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
break;
case VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
case vehicle_command_s::VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
if (cmd->param1 < 0) {
@ -813,7 +813,7 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd) @@ -813,7 +813,7 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd)
}
}
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
break;
default:
@ -822,25 +822,25 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd) @@ -822,25 +822,25 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd)
}
void
BottleDrop::answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result)
BottleDrop::answer_command(struct vehicle_command_s *cmd, unsigned result)
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
case vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED:
break;
case VEHICLE_CMD_RESULT_DENIED:
case vehicle_command_s::VEHICLE_CMD_RESULT_DENIED:
mavlink_log_critical(_mavlink_fd, "command denied: %u", cmd->command);
break;
case VEHICLE_CMD_RESULT_FAILED:
case vehicle_command_s::VEHICLE_CMD_RESULT_FAILED:
mavlink_log_critical(_mavlink_fd, "command failed: %u", cmd->command);
break;
case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
case vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
mavlink_log_critical(_mavlink_fd, "command temporarily rejected: %u", cmd->command);
break;
case VEHICLE_CMD_RESULT_UNSUPPORTED:
case vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED:
mavlink_log_critical(_mavlink_fd, "command unsupported: %u", cmd->command);
break;

12
src/modules/commander/calibration_routines.cpp

@ -508,14 +508,14 @@ void calibrate_cancel_unsubscribe(int cmd_sub) @@ -508,14 +508,14 @@ void calibrate_cancel_unsubscribe(int cmd_sub)
orb_unsubscribe(cmd_sub);
}
static void calibrate_answer_command(int mavlink_fd, struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result)
static void calibrate_answer_command(int mavlink_fd, struct vehicle_command_s &cmd, unsigned result)
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
case vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED:
tune_positive(true);
break;
case VEHICLE_CMD_RESULT_DENIED:
case vehicle_command_s::VEHICLE_CMD_RESULT_DENIED:
mavlink_log_critical(mavlink_fd, "command denied during calibration: %u", cmd.command);
tune_negative(true);
break;
@ -537,18 +537,18 @@ bool calibrate_cancel_check(int mavlink_fd, int cancel_sub) @@ -537,18 +537,18 @@ bool calibrate_cancel_check(int mavlink_fd, int cancel_sub)
orb_copy(ORB_ID(vehicle_command), cancel_sub, &cmd);
if (cmd.command == VEHICLE_CMD_PREFLIGHT_CALIBRATION &&
if (cmd.command == vehicle_command_s::VEHICLE_CMD_PREFLIGHT_CALIBRATION &&
(int)cmd.param1 == 0 &&
(int)cmd.param2 == 0 &&
(int)cmd.param3 == 0 &&
(int)cmd.param4 == 0 &&
(int)cmd.param5 == 0 &&
(int)cmd.param6 == 0) {
calibrate_answer_command(mavlink_fd, cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calibrate_answer_command(mavlink_fd, cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
mavlink_log_critical(mavlink_fd, CAL_QGC_CANCELLED_MSG);
return true;
} else {
calibrate_answer_command(mavlink_fd, cmd, VEHICLE_CMD_RESULT_DENIED);
calibrate_answer_command(mavlink_fd, cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
}
}

163
src/modules/commander/commander.cpp

@ -247,7 +247,7 @@ static void commander_set_home_position(orb_advert_t &homePub, home_position_s & @@ -247,7 +247,7 @@ static void commander_set_home_position(orb_advert_t &homePub, home_position_s &
*/
void *commander_low_prio_loop(void *arg);
void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result);
void answer_command(struct vehicle_command_s &cmd, unsigned result);
int commander_main(int argc, char *argv[])
@ -456,11 +456,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -456,11 +456,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
/* result of the command */
enum VEHICLE_CMD_RESULT cmd_result = VEHICLE_CMD_RESULT_UNSUPPORTED;
unsigned cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
/* request to set different system mode */
switch (cmd->command) {
case VEHICLE_CMD_DO_SET_MODE: {
case vehicle_command_s::VEHICLE_CMD_DO_SET_MODE: {
uint8_t base_mode = (uint8_t)cmd->param1;
uint8_t custom_main_mode = (uint8_t)cmd->param2;
@ -521,15 +521,15 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -521,15 +521,15 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
if (hil_ret != TRANSITION_DENIED && arming_ret != TRANSITION_DENIED && main_ret != TRANSITION_DENIED) {
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
case vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM: {
// Adhere to MAVLink specs, but base on knowledge that these fundamentally encode ints
// for logic state parameters
@ -549,7 +549,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -549,7 +549,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
// Refuse to arm if preflight checks have failed
if (!status.hil_state != vehicle_status_s::HIL_STATE_ON && !status.condition_system_sensors_initialized) {
mavlink_log_critical(mavlink_fd, "Arming DENIED. Preflight checks have failed.");
cmd_result = VEHICLE_CMD_RESULT_DENIED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
break;
}
@ -559,16 +559,16 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -559,16 +559,16 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
if (arming_res == TRANSITION_DENIED) {
mavlink_log_critical(mavlink_fd, "REJECTING component arm cmd");
cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} else {
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
}
}
break;
case VEHICLE_CMD_OVERRIDE_GOTO: {
case vehicle_command_s::VEHICLE_CMD_OVERRIDE_GOTO: {
// TODO listen vehicle_command topic directly from navigator (?)
// Increase by 0.5f and rely on the integer cast
@ -579,12 +579,12 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -579,12 +579,12 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
if (mav_goto == 0) { // MAV_GOTO_DO_HOLD
status_local->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
mavlink_log_critical(mavlink_fd, "Pause mission cmd");
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else if (mav_goto == 1) { // MAV_GOTO_DO_CONTINUE
status_local->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION;
mavlink_log_critical(mavlink_fd, "Continue mission cmd");
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_critical(mavlink_fd, "REJ CMD: %.1f %.1f %.1f %.1f %.1f %.1f %.1f %.1f",
@ -600,7 +600,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -600,7 +600,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
break;
/* Flight termination */
case VEHICLE_CMD_DO_FLIGHTTERMINATION: {
case vehicle_command_s::VEHICLE_CMD_DO_FLIGHTTERMINATION: {
if (cmd->param1 > 0.5f) {
//XXX update state machine?
armed_local->force_failsafe = true;
@ -642,11 +642,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -642,11 +642,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
warnx("rc loss mode commanded");
}
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
break;
case VEHICLE_CMD_DO_SET_HOME: {
case vehicle_command_s::VEHICLE_CMD_DO_SET_HOME: {
bool use_current = cmd->param1 > 0.5f;
if (use_current) {
@ -658,10 +658,10 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -658,10 +658,10 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
home->timestamp = hrt_absolute_time();
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
} else {
@ -672,10 +672,10 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -672,10 +672,10 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
home->timestamp = hrt_absolute_time();
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
if (cmd_result == VEHICLE_CMD_RESULT_ACCEPTED) {
if (cmd_result == vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED) {
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home->lat, home->lon, (double)home->alt);
mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home->lat, home->lon, (double)home->alt);
@ -693,16 +693,16 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -693,16 +693,16 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
break;
case VEHICLE_CMD_NAV_GUIDED_ENABLE: {
case vehicle_command_s::VEHICLE_CMD_NAV_GUIDED_ENABLE: {
transition_result_t res = TRANSITION_DENIED;
static main_state_t main_state_pre_offboard =vehicle_status_s::MAIN_STATE_MANUAL;
static main_state_t main_state_pre_offboard = vehicle_status_s::MAIN_STATE_MANUAL;
if (status_local->main_state !=vehicle_status_s::MAIN_STATE_OFFBOARD) {
if (status_local->main_state != vehicle_status_s::MAIN_STATE_OFFBOARD) {
main_state_pre_offboard = status_local->main_state;
}
if (cmd->param1 > 0.5f) {
res = main_state_transition(status_local,vehicle_status_s::MAIN_STATE_OFFBOARD);
res = main_state_transition(status_local, vehicle_status_s::MAIN_STATE_OFFBOARD);
if (res == TRANSITION_DENIED) {
print_reject_mode(status_local, "OFFBOARD");
@ -722,35 +722,35 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -722,35 +722,35 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
break;
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
case VEHICLE_CMD_PREFLIGHT_STORAGE:
case VEHICLE_CMD_CUSTOM_0:
case VEHICLE_CMD_CUSTOM_1:
case VEHICLE_CMD_CUSTOM_2:
case VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
case VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
case VEHICLE_CMD_DO_MOUNT_CONTROL:
case VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT:
case VEHICLE_CMD_DO_MOUNT_CONFIGURE:
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_STORAGE:
case vehicle_command_s::VEHICLE_CMD_CUSTOM_0:
case vehicle_command_s::VEHICLE_CMD_CUSTOM_1:
case vehicle_command_s::VEHICLE_CMD_CUSTOM_2:
case vehicle_command_s::VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
case vehicle_command_s::VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
case vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL:
case vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT:
case vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE:
/* ignore commands that handled in low prio loop */
break;
default:
/* Warn about unsupported commands, this makes sense because only commands
* to this component ID (or all) are passed by mavlink. */
answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
answer_command(*cmd, vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
if (cmd_result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
if (cmd_result != vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
answer_command(*cmd, cmd_result);
}
/* send any requested ACKs */
if (cmd->confirmation > 0 && cmd_result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
if (cmd->confirmation > 0 && cmd_result != vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* send acknowledge command */
// XXX TODO
}
@ -828,6 +828,7 @@ int commander_thread_main(int argc, char *argv[]) @@ -828,6 +828,7 @@ int commander_thread_main(int argc, char *argv[])
param_t _param_ef_time_thres = param_find("COM_EF_TIME");
param_t _param_autostart_id = param_find("SYS_AUTOSTART");
param_t _param_autosave_params = param_find("COM_AUTOS_PAR");
param_t _param_rc_in_off = param_find("COM_RC_IN_MODE");
const char *main_states_str[vehicle_status_s::MAIN_STATE_MAX];
main_states_str[vehicle_status_s::MAIN_STATE_MANUAL] = "MANUAL";
@ -888,6 +889,7 @@ int commander_thread_main(int argc, char *argv[]) @@ -888,6 +889,7 @@ int commander_thread_main(int argc, char *argv[])
status.condition_landed = true; // initialize to safe value
// We want to accept RC inputs as default
status.rc_input_blocked = false;
status.rc_input_mode = vehicle_status_s::RC_IN_MODE_DEFAULT;
status.main_state =vehicle_status_s::MAIN_STATE_MANUAL;
status.nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
status.arming_state = vehicle_status_s::ARMING_STATE_INIT;
@ -1132,7 +1134,7 @@ int commander_thread_main(int argc, char *argv[]) @@ -1132,7 +1134,7 @@ int commander_thread_main(int argc, char *argv[])
}
// Run preflight check
status.condition_system_sensors_initialized = Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, true, !status.circuit_breaker_engaged_gpsfailure_check);
status.condition_system_sensors_initialized = Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, !status.rc_input_mode, !status.circuit_breaker_engaged_gpsfailure_check);
if (!status.condition_system_sensors_initialized) {
set_tune_override(TONE_GPS_WARNING_TUNE); //sensor fail tune
}
@ -1147,6 +1149,7 @@ int commander_thread_main(int argc, char *argv[]) @@ -1147,6 +1149,7 @@ int commander_thread_main(int argc, char *argv[])
int32_t datalink_loss_enabled = false;
int32_t datalink_loss_timeout = 10;
float rc_loss_timeout = 0.5;
int32_t rc_in_off = 0;
int32_t datalink_regain_timeout = 0;
/* Thresholds for engine failure detection */
@ -1233,6 +1236,8 @@ int commander_thread_main(int argc, char *argv[]) @@ -1233,6 +1236,8 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
param_get(_param_datalink_loss_timeout, &datalink_loss_timeout);
param_get(_param_rc_loss_timeout, &rc_loss_timeout);
param_get(_param_rc_in_off, &rc_in_off);
status.rc_input_mode = rc_in_off;
param_get(_param_datalink_regain_timeout, &datalink_regain_timeout);
param_get(_param_ef_throttle_thres, &ef_throttle_thres);
param_get(_param_ef_current2throttle_thres, &ef_current2throttle_thres);
@ -1305,7 +1310,8 @@ int commander_thread_main(int argc, char *argv[]) @@ -1305,7 +1310,8 @@ int commander_thread_main(int argc, char *argv[])
}
/* provide RC and sensor status feedback to the user */
(void)Commander::preflightCheck(mavlink_fd, true, true, true, true, chAirspeed, true, !status.circuit_breaker_engaged_gpsfailure_check);
(void)Commander::preflightCheck(mavlink_fd, true, true, true, true, chAirspeed,
!(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_OFF), !status.circuit_breaker_engaged_gpsfailure_check);
}
telemetry_last_heartbeat[i] = telemetry.heartbeat_time;
@ -1707,12 +1713,12 @@ int commander_thread_main(int argc, char *argv[]) @@ -1707,12 +1713,12 @@ int commander_thread_main(int argc, char *argv[])
} // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
/* RC input check */
if (!status.rc_input_blocked && sp_man.timestamp != 0 &&
if (!(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_OFF) && !status.rc_input_blocked && sp_man.timestamp != 0 &&
hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) {
/* handle the case where RC signal was regained */
if (!status.rc_signal_found_once) {
status.rc_signal_found_once = true;
mavlink_log_critical(mavlink_fd, "detected RC signal first time");
mavlink_log_info(mavlink_fd, "Detected RC signal first time");
status_changed = true;
} else {
@ -2560,30 +2566,30 @@ print_reject_arm(const char *msg) @@ -2560,30 +2566,30 @@ print_reject_arm(const char *msg)
}
}
void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result)
void answer_command(struct vehicle_command_s &cmd, unsigned result)
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
case vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED:
tune_positive(true);
break;
case VEHICLE_CMD_RESULT_DENIED:
case vehicle_command_s::VEHICLE_CMD_RESULT_DENIED:
mavlink_log_critical(mavlink_fd, "command denied: %u", cmd.command);
tune_negative(true);
break;
case VEHICLE_CMD_RESULT_FAILED:
case vehicle_command_s::VEHICLE_CMD_RESULT_FAILED:
mavlink_log_critical(mavlink_fd, "command failed: %u", cmd.command);
tune_negative(true);
break;
case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
case vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
/* this needs additional hints to the user - so let other messages pass and be spoken */
mavlink_log_critical(mavlink_fd, "command temporarily rejected: %u", cmd.command);
tune_negative(true);
break;
case VEHICLE_CMD_RESULT_UNSUPPORTED:
case vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED:
mavlink_log_critical(mavlink_fd, "command unsupported: %u", cmd.command);
tune_negative(true);
break;
@ -2647,49 +2653,49 @@ void *commander_low_prio_loop(void *arg) @@ -2647,49 +2653,49 @@ void *commander_low_prio_loop(void *arg)
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
/* ignore commands the high-prio loop handles */
if (cmd.command == VEHICLE_CMD_DO_SET_MODE ||
cmd.command == VEHICLE_CMD_COMPONENT_ARM_DISARM ||
cmd.command == VEHICLE_CMD_NAV_TAKEOFF ||
cmd.command == VEHICLE_CMD_DO_SET_SERVO) {
if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_MODE ||
cmd.command == vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM ||
cmd.command == vehicle_command_s::VEHICLE_CMD_NAV_TAKEOFF ||
cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_SERVO) {
continue;
}
/* only handle low-priority commands here */
switch (cmd.command) {
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (is_safe(&status, &safety, &armed)) {
if (((int)(cmd.param1)) == 1) {
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
usleep(100000);
/* reboot */
systemreset(false);
} else if (((int)(cmd.param1)) == 3) {
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
usleep(100000);
/* reboot to bootloader */
systemreset(true);
} else {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
}
} else {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
}
break;
case VEHICLE_CMD_PREFLIGHT_CALIBRATION: {
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_CALIBRATION: {
int calib_ret = ERROR;
/* try to go to INIT/PREFLIGHT arming state */
if (TRANSITION_DENIED == arming_state_transition(&status, &safety, vehicle_status_s::ARMING_STATE_INIT, &armed,
false /* fRunPreArmChecks */, mavlink_fd)) {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
break;
} else {
status.calibration_enabled = true;
@ -2697,21 +2703,21 @@ void *commander_low_prio_loop(void *arg) @@ -2697,21 +2703,21 @@ void *commander_low_prio_loop(void *arg)
if ((int)(cmd.param1) == 1) {
/* gyro calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_gyro_calibration(mavlink_fd);
} else if ((int)(cmd.param2) == 1) {
/* magnetometer calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_mag_calibration(mavlink_fd);
} else if ((int)(cmd.param3) == 1) {
/* zero-altitude pressure calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
} else if ((int)(cmd.param4) == 1) {
/* RC calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
/* disable RC control input completely */
status.rc_input_blocked = true;
calib_ret = OK;
@ -2719,31 +2725,31 @@ void *commander_low_prio_loop(void *arg) @@ -2719,31 +2725,31 @@ void *commander_low_prio_loop(void *arg)
} else if ((int)(cmd.param4) == 2) {
/* RC trim calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_trim_calibration(mavlink_fd);
} else if ((int)(cmd.param5) == 1) {
/* accelerometer calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_accel_calibration(mavlink_fd);
} else if ((int)(cmd.param5) == 2) {
// board offset calibration
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_level_calibration(mavlink_fd);
} else if ((int)(cmd.param6) == 1) {
/* airspeed calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_airspeed_calibration(mavlink_fd);
} else if ((int)(cmd.param7) == 1) {
/* do esc calibration */
answer_command(cmd,VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_esc_calibration(mavlink_fd, &armed);
} else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */
if (status.rc_input_blocked) {
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
/* enable RC control input */
status.rc_input_blocked = false;
mavlink_log_info(mavlink_fd, "CAL: Re-enabling RC IN");
@ -2770,7 +2776,8 @@ void *commander_low_prio_loop(void *arg) @@ -2770,7 +2776,8 @@ void *commander_low_prio_loop(void *arg)
checkAirspeed = true;
}
status.condition_system_sensors_initialized = Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, true, !status.circuit_breaker_engaged_gpsfailure_check);
status.condition_system_sensors_initialized = Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed,
!(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_OFF), !status.circuit_breaker_engaged_gpsfailure_check);
arming_state_transition(&status, &safety, vehicle_status_s::ARMING_STATE_STANDBY, &armed, false /* fRunPreArmChecks */, mavlink_fd);
@ -2781,14 +2788,14 @@ void *commander_low_prio_loop(void *arg) @@ -2781,14 +2788,14 @@ void *commander_low_prio_loop(void *arg)
break;
}
case VEHICLE_CMD_PREFLIGHT_STORAGE: {
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_STORAGE: {
if (((int)(cmd.param1)) == 0) {
int ret = param_load_default();
if (ret == OK) {
mavlink_log_info(mavlink_fd, "settings loaded");
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else {
mavlink_log_critical(mavlink_fd, "settings load ERROR");
@ -2802,7 +2809,7 @@ void *commander_low_prio_loop(void *arg) @@ -2802,7 +2809,7 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "ERROR: %s", strerror(ret));
}
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_FAILED);
}
} else if (((int)(cmd.param1)) == 1) {
@ -2816,7 +2823,7 @@ void *commander_low_prio_loop(void *arg) @@ -2816,7 +2823,7 @@ void *commander_low_prio_loop(void *arg)
}
/* do not spam MAVLink, but provide the answer / green led mechanism */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else {
mavlink_log_critical(mavlink_fd, "settings save error");
@ -2830,14 +2837,14 @@ void *commander_low_prio_loop(void *arg) @@ -2830,14 +2837,14 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "ERROR: %s", strerror(ret));
}
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_FAILED);
}
}
break;
}
case VEHICLE_CMD_START_RX_PAIR:
case vehicle_command_s::VEHICLE_CMD_START_RX_PAIR:
/* handled in the IO driver */
break;
@ -2847,8 +2854,8 @@ void *commander_low_prio_loop(void *arg) @@ -2847,8 +2854,8 @@ void *commander_low_prio_loop(void *arg)
}
/* send any requested ACKs */
if (cmd.confirmation > 0 && cmd.command != VEHICLE_CMD_DO_SET_MODE
&& cmd.command != VEHICLE_CMD_COMPONENT_ARM_DISARM) {
if (cmd.confirmation > 0 && cmd.command != vehicle_command_s::VEHICLE_CMD_DO_SET_MODE
&& cmd.command != vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM) {
/* send acknowledge command */
// XXX TODO
}

14
src/modules/commander/commander_params.c

@ -195,3 +195,17 @@ PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5); @@ -195,3 +195,17 @@ PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5);
* @max 1
*/
PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1);
/**
* RC control input mode
*
* The default value of 0 requires a valid RC transmitter setup.
* Setting this to 1 disables RC input handling and the associated checks. A value of
* 2 will generate RC control data from manual input received via MAVLink instead
* of directly forwarding the manual input data.
*
* @group Commander
* @min 0
* @max 2
*/
PARAM_DEFINE_INT32(COM_RC_IN_MODE, 0);

2
src/modules/commander/state_machine_helper.cpp

@ -692,5 +692,5 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) @@ -692,5 +692,5 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
checkAirspeed = true;
}
return !Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, true, !status->circuit_breaker_engaged_gpsfailure_check, true);
return !Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, !(status->rc_input_mode == vehicle_status_s::RC_IN_MODE_OFF), !status->circuit_breaker_engaged_gpsfailure_check, true);
}

4
src/modules/dataman/dataman.h

@ -62,7 +62,11 @@ extern "C" { @@ -62,7 +62,11 @@ extern "C" {
/** The maximum number of instances for each item type */
enum {
DM_KEY_SAFE_POINTS_MAX = 8,
#ifdef __cplusplus
DM_KEY_FENCE_POINTS_MAX = fence_s::GEOFENCE_MAX_VERTICES,
#else
DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES,
#endif
DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED,
DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED,
DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED,

2
src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp

@ -395,7 +395,7 @@ int AttitudePositionEstimatorEKF::check_filter_state() @@ -395,7 +395,7 @@ int AttitudePositionEstimatorEKF::check_filter_state()
}
}
struct estimator_status_report rep;
struct estimator_status_s rep;
memset(&rep, 0, sizeof(rep));

24
src/modules/fw_att_control/fw_att_control_main.cpp

@ -520,7 +520,7 @@ FixedwingAttitudeControl::vehicle_control_mode_poll() @@ -520,7 +520,7 @@ FixedwingAttitudeControl::vehicle_control_mode_poll()
orb_check(_vcontrol_mode_sub, &vcontrol_mode_updated);
if (vcontrol_mode_updated) {
orb_copy(ORB_ID(vehicle_control_mode), _vcontrol_mode_sub, &_vcontrol_mode);
}
}
@ -619,11 +619,6 @@ FixedwingAttitudeControl::task_main_trampoline(int argc, char *argv[]) @@ -619,11 +619,6 @@ FixedwingAttitudeControl::task_main_trampoline(int argc, char *argv[])
void
FixedwingAttitudeControl::task_main()
{
/* inform about start */
warnx("Initializing..");
fflush(stdout);
/*
* do subscriptions
*/
@ -1154,14 +1149,17 @@ int fw_att_control_main(int argc, char *argv[]) @@ -1154,14 +1149,17 @@ int fw_att_control_main(int argc, char *argv[])
err(1, "start failed");
}
/* avoid memory fragmentation by not exiting start handler until the task has fully started */
while (att_control::g_control == nullptr || !att_control::g_control->task_running()) {
usleep(50000);
printf(".");
fflush(stdout);
}
printf("\n");
/* check if the waiting is necessary at all */
if (att_control::g_control == nullptr || !att_control::g_control->task_running()) {
/* avoid memory fragmentation by not exiting start handler until the task has fully started */
while (att_control::g_control == nullptr || !att_control::g_control->task_running()) {
usleep(50000);
printf(".");
fflush(stdout);
}
printf("\n");
}
exit(0);
}

20
src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp

@ -399,7 +399,7 @@ private: @@ -399,7 +399,7 @@ private:
bool climbout_mode, float climbout_pitch_min_rad,
float altitude,
const math::Vector<3> &ground_speed,
tecs_mode mode = TECS_MODE_NORMAL,
unsigned mode = tecs_status_s::TECS_MODE_NORMAL,
bool pitch_max_special = false);
};
@ -1093,7 +1093,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi @@ -1093,7 +1093,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
0.0f, throttle_max, throttle_land,
false, land_motor_lim ? math::radians(_parameters.land_flare_pitch_min_deg) : math::radians(_parameters.pitch_limit_min),
_global_pos.alt, ground_speed,
land_motor_lim ? TECS_MODE_LAND_THROTTLELIM : TECS_MODE_LAND);
land_motor_lim ? tecs_status_s::TECS_MODE_LAND_THROTTLELIM : tecs_status_s::TECS_MODE_LAND);
if (!land_noreturn_vertical) {
mavlink_log_info(_mavlink_fd, "#audio: Landing, flaring");
@ -1198,7 +1198,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi @@ -1198,7 +1198,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
math::radians(10.0f)),
_global_pos.alt,
ground_speed,
TECS_MODE_TAKEOFF,
tecs_status_s::TECS_MODE_TAKEOFF,
takeoff_pitch_max_deg != _parameters.pitch_limit_max);
/* limit roll motion to ensure enough lift */
@ -1303,7 +1303,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi @@ -1303,7 +1303,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
math::radians(_parameters.pitch_limit_min),
_global_pos.alt,
ground_speed,
TECS_MODE_NORMAL);
tecs_status_s::TECS_MODE_NORMAL);
} else {
_control_mode_current = FW_POSCTRL_MODE_OTHER;
@ -1521,7 +1521,7 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_ @@ -1521,7 +1521,7 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
bool climbout_mode, float climbout_pitch_min_rad,
float altitude,
const math::Vector<3> &ground_speed,
tecs_mode mode, bool pitch_max_special)
unsigned mode, bool pitch_max_special)
{
if (_mTecs.getEnabled()) {
/* Using mtecs library: prepare arguments for mtecs call */
@ -1559,7 +1559,7 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_ @@ -1559,7 +1559,7 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
}
/* No underspeed protection in landing mode */
_tecs.set_detect_underspeed_enabled(!(mode == TECS_MODE_LAND || mode == TECS_MODE_LAND_THROTTLELIM));
_tecs.set_detect_underspeed_enabled(!(mode == tecs_status_s::TECS_MODE_LAND || mode == tecs_status_s::TECS_MODE_LAND_THROTTLELIM));
/* Using tecs library */
_tecs.update_pitch_throttle(_R_nb, _att.pitch, altitude, alt_sp, v_sp,
@ -1577,16 +1577,16 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_ @@ -1577,16 +1577,16 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
switch (s.mode) {
case TECS::ECL_TECS_MODE_NORMAL:
t.mode = TECS_MODE_NORMAL;
t.mode = tecs_status_s::TECS_MODE_NORMAL;
break;
case TECS::ECL_TECS_MODE_UNDERSPEED:
t.mode = TECS_MODE_UNDERSPEED;
t.mode = tecs_status_s::TECS_MODE_UNDERSPEED;
break;
case TECS::ECL_TECS_MODE_BAD_DESCENT:
t.mode = TECS_MODE_BAD_DESCENT;
t.mode = tecs_status_s::TECS_MODE_BAD_DESCENT;
break;
case TECS::ECL_TECS_MODE_CLIMBOUT:
t.mode = TECS_MODE_CLIMBOUT;
t.mode = tecs_status_s::TECS_MODE_CLIMBOUT;
break;
}

18
src/modules/fw_pos_control_l1/mtecs/mTecs.cpp

@ -83,7 +83,7 @@ mTecs::~mTecs() @@ -83,7 +83,7 @@ mTecs::~mTecs()
}
int mTecs::updateAltitudeSpeed(float flightPathAngle, float altitude, float altitudeSp, float airspeed,
float airspeedSp, tecs_mode mode, LimitOverride limitOverride)
float airspeedSp, unsigned mode, LimitOverride limitOverride)
{
/* check if all input arguments are numbers and abort if not so */
if (!isfinite(flightPathAngle) || !isfinite(altitude) ||
@ -118,7 +118,7 @@ int mTecs::updateAltitudeSpeed(float flightPathAngle, float altitude, float alti @@ -118,7 +118,7 @@ int mTecs::updateAltitudeSpeed(float flightPathAngle, float altitude, float alti
}
int mTecs::updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAngleSp, float airspeed,
float airspeedSp, tecs_mode mode, LimitOverride limitOverride)
float airspeedSp, unsigned mode, LimitOverride limitOverride)
{
/* check if all input arguments are numbers and abort if not so */
if (!isfinite(flightPathAngle) || !isfinite(flightPathAngleSp) ||
@ -154,7 +154,7 @@ int mTecs::updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAng @@ -154,7 +154,7 @@ int mTecs::updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAng
}
int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flightPathAngleSp, float airspeedFiltered,
float accelerationLongitudinalSp, tecs_mode mode, LimitOverride limitOverride)
float accelerationLongitudinalSp, unsigned mode, LimitOverride limitOverride)
{
/* check if all input arguments are numbers and abort if not so */
if (!isfinite(flightPathAngle) || !isfinite(flightPathAngleSp) ||
@ -200,23 +200,23 @@ int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flight @@ -200,23 +200,23 @@ int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flight
}
/* Check airspeed: if below safe value switch to underspeed mode (if not in land or takeoff mode) */
if (mode != TECS_MODE_LAND && mode != TECS_MODE_TAKEOFF && airspeedFiltered < _airspeedMin.get()) {
mode = TECS_MODE_UNDERSPEED;
if (mode != tecs_status_s::TECS_MODE_LAND && mode != tecs_status_s::TECS_MODE_TAKEOFF && airspeedFiltered < _airspeedMin.get()) {
mode = tecs_status_s::TECS_MODE_UNDERSPEED;
}
/* Set special ouput limiters if we are not in TECS_MODE_NORMAL */
BlockOutputLimiter *outputLimiterThrottle = &_controlTotalEnergy.getOutputLimiter();
BlockOutputLimiter *outputLimiterPitch = &_controlEnergyDistribution.getOutputLimiter();
if (mode == TECS_MODE_TAKEOFF) {
if (mode == tecs_status_s::TECS_MODE_TAKEOFF) {
outputLimiterThrottle = &_BlockOutputLimiterTakeoffThrottle;
outputLimiterPitch = &_BlockOutputLimiterTakeoffPitch;
} else if (mode == TECS_MODE_LAND) {
} else if (mode == tecs_status_s::TECS_MODE_LAND) {
// only limit pitch but do not limit throttle
outputLimiterPitch = &_BlockOutputLimiterLandPitch;
} else if (mode == TECS_MODE_LAND_THROTTLELIM) {
} else if (mode == tecs_status_s::TECS_MODE_LAND_THROTTLELIM) {
outputLimiterThrottle = &_BlockOutputLimiterLandThrottle;
outputLimiterPitch = &_BlockOutputLimiterLandPitch;
} else if (mode == TECS_MODE_UNDERSPEED) {
} else if (mode == tecs_status_s::TECS_MODE_UNDERSPEED) {
outputLimiterThrottle = &_BlockOutputLimiterUnderspeedThrottle;
outputLimiterPitch = &_BlockOutputLimiterUnderspeedPitch;
}

6
src/modules/fw_pos_control_l1/mtecs/mTecs.h

@ -65,19 +65,19 @@ public: @@ -65,19 +65,19 @@ public:
* Control in altitude setpoint and speed mode
*/
int updateAltitudeSpeed(float flightPathAngle, float altitude, float altitudeSp, float airspeed,
float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
float airspeedSp, unsigned mode, LimitOverride limitOverride);
/*
* Control in flightPathAngle setpoint (flollow a slope etc.) and speed mode
*/
int updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAngleSp, float airspeed,
float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
float airspeedSp, unsigned mode, LimitOverride limitOverride);
/*
* Control in flightPathAngle setpoint (flollow a slope etc.) and acceleration mode (base case)
*/
int updateFlightPathAngleAcceleration(float flightPathAngle, float flightPathAngleSp, float airspeedFiltered,
float accelerationLongitudinalSp, tecs_mode mode, LimitOverride limitOverride);
float accelerationLongitudinalSp, unsigned mode, LimitOverride limitOverride);
/*
* Reset all integrators

28
src/modules/land_detector/land_detector_main.cpp

@ -151,20 +151,26 @@ static int land_detector_start(const char *mode) @@ -151,20 +151,26 @@ static int land_detector_start(const char *mode)
/* avoid memory fragmentation by not exiting start handler until the task has fully started */
const uint32_t timeout = hrt_absolute_time() + 5000000; //5 second timeout
while (!land_detector_task->isRunning()) {
usleep(50000);
printf(".");
fflush(stdout);
if (hrt_absolute_time() > timeout) {
err(1, "start failed - timeout");
land_detector_stop();
exit(1);
/* avoid printing dots just yet and do one sleep before the first check */
usleep(10000);
/* check if the waiting involving dots and a newline are still needed */
if (!land_detector_task->isRunning()) {
while (!land_detector_task->isRunning()) {
printf(".");
fflush(stdout);
usleep(50000);
if (hrt_absolute_time() > timeout) {
err(1, "start failed - timeout");
land_detector_stop();
exit(1);
}
}
printf("\n");
}
printf("\n");
//Remember current active mode
strncpy(_currentMode, mode, 12);

9
src/modules/mavlink/mavlink_main.cpp

@ -123,6 +123,7 @@ Mavlink::Mavlink() : @@ -123,6 +123,7 @@ Mavlink::Mavlink() :
_mavlink_fd(-1),
_task_running(false),
_hil_enabled(false),
_generate_rc(false),
_use_hil_gps(false),
_forward_externalsp(false),
_is_usb_uart(false),
@ -745,7 +746,7 @@ Mavlink::get_free_tx_buf() @@ -745,7 +746,7 @@ Mavlink::get_free_tx_buf()
if (_last_write_try_time != 0 &&
hrt_elapsed_time(&_last_write_success_time) > 500 * 1000UL &&
_last_write_success_time != _last_write_try_time) {
warnx("DISABLING HARDWARE FLOW CONTROL");
warnx("Disabling hardware flow control");
enable_flow_control(false);
}
}
@ -876,7 +877,7 @@ Mavlink::handle_message(const mavlink_message_t *msg) @@ -876,7 +877,7 @@ Mavlink::handle_message(const mavlink_message_t *msg)
/* handle packet with parameter component */
_parameters_manager->handle_message(msg);
/* handle packet with ftp component */
_mavlink_ftp->handle_message(msg);
@ -1420,7 +1421,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1420,7 +1421,7 @@ Mavlink::task_main(int argc, char *argv[])
_mavlink_ftp = (MavlinkFTP *) MavlinkFTP::new_instance(this);
_mavlink_ftp->set_interval(interval_from_rate(80.0f));
LL_APPEND(_streams, _mavlink_ftp);
/* MISSION_STREAM stream, actually sends all MISSION_XXX messages at some rate depending on
* remote requests rate. Rate specified here controls how much bandwidth we will reserve for
* mission messages. */
@ -1497,6 +1498,8 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1497,6 +1498,8 @@ Mavlink::task_main(int argc, char *argv[])
if (status_sub->update(&status_time, &status)) {
/* switch HIL mode if required */
set_hil_enabled(status.hil_state == vehicle_status_s::HIL_STATE_ON);
set_manual_input_mode_generation(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_GENERATED);
}
/* check for requested subscriptions */

18
src/modules/mavlink/mavlink_main.h

@ -170,6 +170,23 @@ public: @@ -170,6 +170,23 @@ public:
*/
int set_hil_enabled(bool hil_enabled);
/**
* Set manual input generation mode
*
* Set to true to generate RC_INPUT messages on the system bus from
* MAVLink messages.
*
* @param generation_enabled If set to true, generate RC_INPUT messages
*/
void set_manual_input_mode_generation(bool generation_enabled) { _generate_rc = generation_enabled; }
/**
* Get the manual input generation mode
*
* @return true if manual inputs should generate RC data
*/
bool get_manual_input_mode_generation() { return _generate_rc; }
void send_message(const uint8_t msgid, const void *msg, uint8_t component_ID = 0);
/**
@ -287,6 +304,7 @@ private: @@ -287,6 +304,7 @@ private:
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
bool _generate_rc; /**< Generate RC messages from manual input MAVLink messages */
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
bool _forward_externalsp; /**< Forward external setpoint messages to controllers directly if in offboard mode */
bool _is_usb_uart; /**< Port is USB */

103
src/modules/mavlink/mavlink_receiver.cpp

@ -56,6 +56,7 @@ @@ -56,6 +56,7 @@
#include <drivers/drv_mag.h>
#include <drivers/drv_baro.h>
#include <drivers/drv_range_finder.h>
#include <drivers/drv_rc_input.h>
#include <time.h>
#include <float.h>
#include <unistd.h>
@ -301,7 +302,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg) @@ -301,7 +302,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
vcmd.param6 = cmd_mavlink.param6;
vcmd.param7 = cmd_mavlink.param7;
// XXX do proper translation
vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command;
vcmd.command = cmd_mavlink.command;
vcmd.target_system = cmd_mavlink.target_system;
vcmd.target_component = cmd_mavlink.target_component;
vcmd.source_system = msg->sysid;
@ -358,7 +359,7 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg) @@ -358,7 +359,7 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
vcmd.param6 = ((double)cmd_mavlink.y) / 1e7;
vcmd.param7 = cmd_mavlink.z;
// XXX do proper translation
vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command;
vcmd.command = cmd_mavlink.command;
vcmd.target_system = cmd_mavlink.target_system;
vcmd.target_component = cmd_mavlink.target_component;
vcmd.source_system = msg->sysid;
@ -480,7 +481,7 @@ MavlinkReceiver::handle_message_set_mode(mavlink_message_t *msg) @@ -480,7 +481,7 @@ MavlinkReceiver::handle_message_set_mode(mavlink_message_t *msg)
vcmd.param5 = 0;
vcmd.param6 = 0;
vcmd.param7 = 0;
vcmd.command = VEHICLE_CMD_DO_SET_MODE;
vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_SET_MODE;
vcmd.target_system = new_mode.target_system;
vcmd.target_component = MAV_COMP_ID_ALL;
vcmd.source_system = msg->sysid;
@ -721,7 +722,7 @@ MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg) @@ -721,7 +722,7 @@ MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg)
mavlink_vision_position_estimate_t pos;
mavlink_msg_vision_position_estimate_decode(msg, &pos);
struct vision_position_estimate vision_position;
struct vision_position_estimate_s vision_position;
memset(&vision_position, 0, sizeof(vision_position));
// Use the component ID to identify the vision sensor
@ -899,28 +900,100 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) @@ -899,28 +900,100 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
}
}
static switch_pos_t decode_switch_pos(uint16_t buttons, int sw) {
return (buttons >> (sw * 2)) & 3;
}
static int decode_switch_pos_n(uint16_t buttons, int sw) {
if (buttons & (1 << sw)) {
return 1;
} else {
return 0;
}
}
void
MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
{
mavlink_manual_control_t man;
mavlink_msg_manual_control_decode(msg, &man);
struct manual_control_setpoint_s manual;
memset(&manual, 0, sizeof(manual));
// Check target
if (man.target != 0 && man.target != _mavlink->get_system_id()) {
return;
}
if (_mavlink->get_manual_input_mode_generation()) {
struct rc_input_values rc = {};
rc.timestamp_publication = hrt_absolute_time();
rc.timestamp_last_signal = rc.timestamp_publication;
manual.timestamp = hrt_absolute_time();
manual.x = man.x / 1000.0f;
manual.y = man.y / 1000.0f;
manual.r = man.r / 1000.0f;
manual.z = man.z / 1000.0f;
rc.channel_count = 8;
rc.rc_failsafe = false;
rc.rc_lost = false;
rc.rc_lost_frame_count = 0;
rc.rc_total_frame_count = 1;
rc.rc_ppm_frame_length = 0;
rc.input_source = RC_INPUT_SOURCE_MAVLINK;
rc.rssi = RC_INPUT_RSSI_MAX;
// warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, (double)manual.z);
/* roll */
rc.values[0] = man.x / 2 + 1500;
/* pitch */
rc.values[1] = man.y / 2 + 1500;
if (_manual_pub < 0) {
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
/*
* yaw needs special handling as some joysticks have a circular mechanical mask,
* which makes the corner positions unreachable.
* scale yaw up and clip it to overcome this.
*/
rc.values[2] = man.r / 1.2f + 1500;
if (rc.values[2] > 2000) {
rc.values[2] = 2000;
} else if (rc.values[2] < 1000) {
rc.values[2] = 1000;
}
/* throttle */
rc.values[3] = man.z + 1000;
rc.values[4] = decode_switch_pos_n(man.buttons, 0) * 1000 + 1000;
rc.values[5] = decode_switch_pos_n(man.buttons, 1) * 1000 + 1000;
rc.values[6] = decode_switch_pos_n(man.buttons, 2) * 1000 + 1000;
rc.values[7] = decode_switch_pos_n(man.buttons, 3) * 1000 + 1000;
rc.values[8] = decode_switch_pos_n(man.buttons, 4) * 1000 + 1000;
rc.values[9] = decode_switch_pos_n(man.buttons, 5) * 1000 + 1000;
if (_rc_pub <= 0) {
_rc_pub = orb_advertise(ORB_ID(input_rc), &rc);
} else {
orb_publish(ORB_ID(input_rc), _rc_pub, &rc);
}
} else {
orb_publish(ORB_ID(manual_control_setpoint), _manual_pub, &manual);
struct manual_control_setpoint_s manual = {};
manual.timestamp = hrt_absolute_time();
manual.x = man.x / 1000.0f;
manual.y = man.y / 1000.0f;
manual.r = man.r / 1000.0f;
manual.z = man.z / 1000.0f;
manual.mode_switch = decode_switch_pos(man.buttons, 0);
manual.return_switch = decode_switch_pos(man.buttons, 1);
manual.posctl_switch = decode_switch_pos(man.buttons, 2);
manual.loiter_switch = decode_switch_pos(man.buttons, 3);
manual.acro_switch = decode_switch_pos(man.buttons, 4);
manual.offboard_switch = decode_switch_pos(man.buttons, 5);
if (_manual_pub < 0) {
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
} else {
orb_publish(ORB_ID(manual_control_setpoint), _manual_pub, &manual);
}
}
}

4
src/modules/navigator/geofence.cpp

@ -259,8 +259,8 @@ Geofence::valid() @@ -259,8 +259,8 @@ Geofence::valid()
}
// Otherwise
if ((_verticesCount < 4) || (_verticesCount > GEOFENCE_MAX_VERTICES)) {
warnx("Fence must have at least 3 sides and not more than %d", GEOFENCE_MAX_VERTICES - 1);
if ((_verticesCount < 4) || (_verticesCount > fence_s::GEOFENCE_MAX_VERTICES)) {
warnx("Fence must have at least 3 sides and not more than %d", fence_s::GEOFENCE_MAX_VERTICES - 1);
return false;
}

6
src/modules/navigator/mission_feasibility_checker.cpp

@ -127,7 +127,7 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss @@ -127,7 +127,7 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
}
if (!geofence.inside_polygon(missionitem.lat, missionitem.lon, missionitem.altitude)) {
mavlink_log_critical(_mavlink_fd, "Geofence violation waypoint %d", i);
mavlink_log_critical(_mavlink_fd, "Geofence violation for waypoint %d", i);
return false;
}
}
@ -177,7 +177,7 @@ bool MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, s @@ -177,7 +177,7 @@ bool MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, s
if (dm_read(dm_current, i, &missionitem, len) != len) {
// not supposed to happen unless the datamanager can't access the SD card, etc.
mavlink_log_critical(_mavlink_fd, "Rejecting Mission: Cannot access mission from SD card");
mavlink_log_critical(_mavlink_fd, "Rejecting Mission: Cannot access SD card");
return false;
}
@ -197,7 +197,7 @@ bool MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, s @@ -197,7 +197,7 @@ bool MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, s
return false;
}
}
mavlink_log_critical(_mavlink_fd, "Mission is valid!");
mavlink_log_info(_mavlink_fd, "Mission ready.");
return true;
}

5
src/modules/navigator/navigator_main.cpp

@ -268,10 +268,9 @@ Navigator::task_main() @@ -268,10 +268,9 @@ Navigator::task_main()
} else {
mavlink_log_info(_mavlink_fd, "No geofence set");
if (_geofence.clearDm() > 0)
warnx("Geofence cleared");
else
if (_geofence.clearDm() != OK) {
warnx("Could not clear geofence");
}
}
/* do subscriptions */

6
src/modules/position_estimator_inav/position_estimator_inav_main.c

@ -325,7 +325,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) @@ -325,7 +325,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
memset(&local_pos, 0, sizeof(local_pos));
struct optical_flow_s flow;
memset(&flow, 0, sizeof(flow));
struct vision_position_estimate vision;
struct vision_position_estimate_s vision;
memset(&vision, 0, sizeof(vision));
struct vehicle_global_position_s global_pos;
memset(&global_pos, 0, sizeof(global_pos));
@ -389,8 +389,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) @@ -389,8 +389,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
} else {
wait_baro = false;
baro_offset /= (float) baro_init_cnt;
warnx("baro offs: %d", (int)baro_offset);
mavlink_log_info(mavlink_fd, "[inav] baro offs: %d", (int)baro_offset);
warnx("baro offset: %d m", (int)baro_offset);
mavlink_log_info(mavlink_fd, "[inav] baro offset: %d m", (int)baro_offset);
local_pos.z_valid = true;
local_pos.v_z_valid = true;
}

5
src/modules/px4iofirmware/mixer.cpp

@ -234,7 +234,7 @@ mixer_tick(void) @@ -234,7 +234,7 @@ mixer_tick(void)
in_mixer = false;
/* the pwm limit call takes care of out of band errors */
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
pwm_limit_calc(should_arm, mixed, r_setup_pwm_reverse, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
r_page_servos[i] = 0;
@ -272,8 +272,9 @@ mixer_tick(void) @@ -272,8 +272,9 @@ mixer_tick(void)
if (mixer_servos_armed && should_arm) {
/* update the servo outputs. */
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
up_pwm_servo_set(i, r_page_servos[i]);
}
/* set S.BUS1 or S.BUS2 outputs */

2
src/modules/px4iofirmware/protocol.h

@ -233,6 +233,8 @@ enum { /* DSM bind states */ @@ -233,6 +233,8 @@ enum { /* DSM bind states */
#define PX4IO_P_SETUP_FORCE_SAFETY_ON 14 /* force safety switch into 'disarmed' (PWM disabled state) */
#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
#define PX4IO_P_SETUP_PWM_REVERSE 15 /**< Bitmask to reverse PWM channels 1-8 */
/* autopilot control values, -10000..10000 */
#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */

2
src/modules/px4iofirmware/px4io.h

@ -111,6 +111,8 @@ extern uint16_t r_page_servo_disarmed[]; /* PX4IO_PAGE_DISARMED_PWM */ @@ -111,6 +111,8 @@ extern uint16_t r_page_servo_disarmed[]; /* PX4IO_PAGE_DISARMED_PWM */
#endif
#define r_setup_rc_thr_failsafe r_page_setup[PX4IO_P_SETUP_RC_THR_FAILSAFE_US]
#define r_setup_pwm_reverse r_page_setup[PX4IO_P_SETUP_PWM_REVERSE]
#define r_control_values (&r_page_controls[0])
/*

5
src/modules/px4iofirmware/registers.c

@ -173,6 +173,7 @@ volatile uint16_t r_page_setup[] = @@ -173,6 +173,7 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_REBOOT_BL] = 0,
[PX4IO_P_SETUP_CRC ... (PX4IO_P_SETUP_CRC+1)] = 0,
[PX4IO_P_SETUP_RC_THR_FAILSAFE_US] = 0,
[PX4IO_P_SETUP_PWM_REVERSE] = 0,
};
#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
@ -622,6 +623,10 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) @@ -622,6 +623,10 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
}
break;
case PX4IO_P_SETUP_PWM_REVERSE:
r_page_setup[PX4IO_P_SETUP_PWM_REVERSE] = value;
break;
default:
return -1;
}

4
src/modules/sdlog2/sdlog2.c

@ -1069,7 +1069,7 @@ int sdlog2_thread_main(int argc, char *argv[]) @@ -1069,7 +1069,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_global_position_s global_pos;
struct position_setpoint_triplet_s triplet;
struct vehicle_vicon_position_s vicon_pos;
struct vision_position_estimate vision_pos;
struct vision_position_estimate_s vision_pos;
struct optical_flow_s flow;
struct rc_channels_s rc;
struct differential_pressure_s diff_pres;
@ -1079,7 +1079,7 @@ int sdlog2_thread_main(int argc, char *argv[]) @@ -1079,7 +1079,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct battery_status_s battery;
struct telemetry_status_s telemetry;
struct range_finder_report range_finder;
struct estimator_status_report estimator_status;
struct estimator_status_s estimator_status;
struct tecs_status_s tecs_status;
struct system_power_s system_power;
struct servorail_status_s servorail_status;

21
src/modules/systemlib/pwm_limit/pwm_limit.c

@ -53,7 +53,9 @@ void pwm_limit_init(pwm_limit_t *limit) @@ -53,7 +53,9 @@ void pwm_limit_init(pwm_limit_t *limit)
return;
}
void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit)
void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t reverse_mask,
const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm,
const float *output, uint16_t *effective_pwm, pwm_limit_t *limit)
{
/* first evaluate state changes */
@ -134,7 +136,13 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_ @@ -134,7 +136,13 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
ramp_min_pwm = min_pwm[i];
}
effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
float control_value = output[i];
if (reverse_mask & (1 << i)) {
control_value = -1.0f * control_value;
}
effective_pwm[i] = control_value * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
/* last line of defense against invalid inputs */
if (effective_pwm[i] < ramp_min_pwm) {
@ -147,7 +155,14 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_ @@ -147,7 +155,14 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
break;
case PWM_LIMIT_STATE_ON:
for (unsigned i=0; i<num_channels; i++) {
effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
float control_value = output[i];
if (reverse_mask & (1 << i)) {
control_value = -1.0f * control_value;
}
effective_pwm[i] = control_value * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
/* last line of defense against invalid inputs */
if (effective_pwm[i] < min_pwm[i]) {

2
src/modules/systemlib/pwm_limit/pwm_limit.h

@ -72,7 +72,7 @@ typedef struct { @@ -72,7 +72,7 @@ typedef struct {
__EXPORT void pwm_limit_init(pwm_limit_t *limit);
__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm,
__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t reverse_mask, const uint16_t *disarmed_pwm,
const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
__END_DECLS

13
src/modules/uORB/objects_common.cpp

@ -130,9 +130,6 @@ ORB_DEFINE(vehicle_control_mode, struct vehicle_control_mode_s); @@ -130,9 +130,6 @@ ORB_DEFINE(vehicle_control_mode, struct vehicle_control_mode_s);
#include "topics/vehicle_local_position_setpoint.h"
ORB_DEFINE(vehicle_local_position_setpoint, struct vehicle_local_position_setpoint_s);
#include "topics/vehicle_bodyframe_speed_setpoint.h"
ORB_DEFINE(vehicle_bodyframe_speed_setpoint, struct vehicle_bodyframe_speed_setpoint_s);
#include "topics/position_setpoint_triplet.h"
ORB_DEFINE(position_setpoint_triplet, struct position_setpoint_triplet_s);
@ -160,9 +157,6 @@ ORB_DEFINE(fw_virtual_attitude_setpoint, struct vehicle_attitude_setpoint_s); @@ -160,9 +157,6 @@ ORB_DEFINE(fw_virtual_attitude_setpoint, struct vehicle_attitude_setpoint_s);
#include "topics/manual_control_setpoint.h"
ORB_DEFINE(manual_control_setpoint, struct manual_control_setpoint_s);
#include "topics/vehicle_control_debug.h"
ORB_DEFINE(vehicle_control_debug, struct vehicle_control_debug_s);
#include "topics/offboard_control_mode.h"
ORB_DEFINE(offboard_control_mode, struct offboard_control_mode_s);
@ -172,9 +166,6 @@ ORB_DEFINE(optical_flow, struct optical_flow_s); @@ -172,9 +166,6 @@ ORB_DEFINE(optical_flow, struct optical_flow_s);
#include "topics/filtered_bottom_flow.h"
ORB_DEFINE(filtered_bottom_flow, struct filtered_bottom_flow_s);
#include "topics/omnidirectional_flow.h"
ORB_DEFINE(omnidirectional_flow, struct omnidirectional_flow_s);
#include "topics/airspeed.h"
ORB_DEFINE(airspeed, struct airspeed_s);
@ -234,10 +225,10 @@ ORB_DEFINE(esc_status, struct esc_status_s); @@ -234,10 +225,10 @@ ORB_DEFINE(esc_status, struct esc_status_s);
ORB_DEFINE(encoders, struct encoders_s);
#include "topics/estimator_status.h"
ORB_DEFINE(estimator_status, struct estimator_status_report);
ORB_DEFINE(estimator_status, struct estimator_status_s);
#include "topics/vision_position_estimate.h"
ORB_DEFINE(vision_position_estimate, struct vision_position_estimate);
ORB_DEFINE(vision_position_estimate, struct vision_position_estimate_s);
#include "topics/vehicle_force_setpoint.h"
ORB_DEFINE(vehicle_force_setpoint, struct vehicle_force_setpoint_s);

69
src/modules/uORB/topics/actuator_direct.h

@ -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

73
src/modules/uORB/topics/actuator_outputs.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

68
src/modules/uORB/topics/airspeed.h

@ -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

69
src/modules/uORB/topics/battery_status.h

@ -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

76
src/modules/uORB/topics/debug_key_value.h

@ -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

71
src/modules/uORB/topics/differential_pressure.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 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

66
src/modules/uORB/topics/encoders.h

@ -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

116
src/modules/uORB/topics/esc_status.h

@ -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

80
src/modules/uORB/topics/estimator_status.h

@ -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

80
src/modules/uORB/topics/fence.h

@ -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

64
src/modules/uORB/topics/geofence_result.h

@ -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

76
src/modules/uORB/topics/omnidirectional_flow.h

@ -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

67
src/modules/uORB/topics/servorail_status.h

@ -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

96
src/modules/uORB/topics/subsystem_info.h

@ -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_ */

71
src/modules/uORB/topics/system_power.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

94
src/modules/uORB/topics/tecs_status.h

@ -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

70
src/modules/uORB/topics/test_motor.h

@ -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

68
src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h

@ -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

172
src/modules/uORB/topics/vehicle_command.h

@ -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

86
src/modules/uORB/topics/vehicle_control_debug.h

@ -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

63
src/modules/uORB/topics/vehicle_land_detected.h

@ -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__

77
src/modules/uORB/topics/vehicle_vicon_position.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

82
src/modules/uORB/topics/vision_position_estimate.h

@ -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_ */

68
src/modules/uORB/topics/vtol_vehicle_status.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

68
src/modules/uORB/topics/wind_estimate.h

@ -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…
Cancel
Save