aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB/topics
diff options
context:
space:
mode:
authorJulian Oes <joes@student.ethz.ch>2013-03-11 11:01:49 -0700
committerJulian Oes <joes@student.ethz.ch>2013-03-11 11:01:49 -0700
commit591cc0ac4d17f7ade66fb7b9b248e403a8172d56 (patch)
tree7382ef04263fb4df6c7603c4db9f6c290b24323b /apps/uORB/topics
parent0fe5aeb02c6ab0ac9c50f54d028cd5dde908e051 (diff)
parent1d444f80a3b9b575681e41b7a3a9b26a4b3d606d (diff)
downloadpx4-firmware-591cc0ac4d17f7ade66fb7b9b248e403a8172d56.tar.gz
px4-firmware-591cc0ac4d17f7ade66fb7b9b248e403a8172d56.tar.bz2
px4-firmware-591cc0ac4d17f7ade66fb7b9b248e403a8172d56.zip
Merge remote-tracking branch 'upstream/master' into new_state_machine
Conflicts: apps/commander/commander.c apps/uORB/topics/vehicle_status.h
Diffstat (limited to 'apps/uORB/topics')
-rw-r--r--apps/uORB/topics/differential_pressure.h9
-rw-r--r--apps/uORB/topics/subsystem_info.h3
-rw-r--r--apps/uORB/topics/vehicle_status.h14
3 files changed, 14 insertions, 12 deletions
diff --git a/apps/uORB/topics/differential_pressure.h b/apps/uORB/topics/differential_pressure.h
index fd7670cbc..d5e4bf37e 100644
--- a/apps/uORB/topics/differential_pressure.h
+++ b/apps/uORB/topics/differential_pressure.h
@@ -49,15 +49,16 @@
*/
/**
- * Battery voltages and status
+ * Differential pressure and airspeed
*/
struct differential_pressure_s {
- uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
+ uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
float static_pressure_mbar; /**< Static / environment pressure */
float differential_pressure_mbar; /**< Differential pressure reading */
float temperature_celcius; /**< ambient temperature in celcius, -1 if unknown */
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 true_airspeed_m_s; /**< true airspeed in meters per second, -1 if unknown */
+ float voltage; /**< Voltage from the airspeed sensor (voltage divider already compensated) */
};
/**
@@ -67,4 +68,4 @@ struct differential_pressure_s {
/* register this as object request broker structure */
ORB_DECLARE(differential_pressure);
-#endif \ No newline at end of file
+#endif
diff --git a/apps/uORB/topics/subsystem_info.h b/apps/uORB/topics/subsystem_info.h
index c3e039d66..c415e832e 100644
--- a/apps/uORB/topics/subsystem_info.h
+++ b/apps/uORB/topics/subsystem_info.h
@@ -71,7 +71,8 @@ enum SUBSYSTEM_TYPE
SUBSYSTEM_TYPE_YAWPOSITION = 4096,
SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384,
SUBSYSTEM_TYPE_POSITIONCONTROL = 32768,
- SUBSYSTEM_TYPE_MOTORCONTROL = 65536
+ SUBSYSTEM_TYPE_MOTORCONTROL = 65536,
+ SUBSYSTEM_TYPE_RANGEFINDER = 131072
};
/**
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index eba5a5047..6d3f8a863 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -191,12 +191,16 @@ struct vehicle_status_s
bool condition_auto_mission_available;
bool condition_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
bool condition_launch_position_valid; /**< indicates a valid launch position */
- bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
+ bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
bool condition_local_position_valid;
+ bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
+
+ // bool condition_auto_flight_mode_ok; /**< conditions of auto flight mode apply plus a valid takeoff position lock has been aquired */
+ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
bool flag_fmu_armed; /**< true is motors / actuators of FMU are armed */
- bool flag_io_armed; /**< true is motors / actuators of IO are armed */
+ bool flag_io_armed; /**< true is motors / actuators of IO are armed */
bool flag_system_emergency;
bool flag_preflight_calibration;
@@ -208,10 +212,10 @@ struct vehicle_status_s
bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
bool flag_control_position_enabled; /**< true if position is controlled */
-
// bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
// bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
// bool flag_preflight_accel_calibration;
+ // bool flag_preflight_airspeed_calibration;
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception is terminally lost */
@@ -242,10 +246,6 @@ struct vehicle_status_s
uint16_t errors_count3;
uint16_t errors_count4;
- // bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
- // bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
- bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
-
};
/**