aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-03-19 20:01:01 +0400
committerAnton Babushkin <anton.babushkin@me.com>2014-03-19 20:01:01 +0400
commit9b71e660ad86cb2ecec4db93795f417a9ba0fddd (patch)
treec7bd62f4e4b260f03c6103e9d322e2b3f84d11c2 /src/modules/uORB
parent068b7526b74c9bbcc31acc28f0d578ed9c0f97b1 (diff)
parent295f87f22cc471fccb44e3f3dee3e8fcab263de2 (diff)
downloadpx4-firmware-9b71e660ad86cb2ecec4db93795f417a9ba0fddd.tar.gz
px4-firmware-9b71e660ad86cb2ecec4db93795f417a9ba0fddd.tar.bz2
px4-firmware-9b71e660ad86cb2ecec4db93795f417a9ba0fddd.zip
Merge branch 'beta_mavlink2' into mpc_local_pos_mavlink
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/topics/mission_result.h3
-rw-r--r--src/modules/uORB/topics/sensor_combined.h17
-rwxr-xr-xsrc/modules/uORB/topics/vehicle_attitude.h2
3 files changed, 11 insertions, 11 deletions
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
index c99706b97..7c3921198 100644
--- a/src/modules/uORB/topics/mission_result.h
+++ b/src/modules/uORB/topics/mission_result.h
@@ -54,7 +54,8 @@
struct mission_result_s
{
bool mission_reached; /**< true if mission has been reached */
- unsigned mission_index; /**< index of the mission which has been reached */
+ unsigned mission_index_reached; /**< index of the mission which has been reached */
+ unsigned index_current_mission; /**< index of the current mission */
};
/**
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index ad164555e..92812efd4 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -77,34 +77,33 @@ struct sensor_combined_s {
/* NOTE: Ordering of fields optimized to align to 32 bit / 4 bytes Change with consideration only */
- uint64_t timestamp; /**< Timestamp in microseconds since boot */
+ uint64_t timestamp; /**< Timestamp in microseconds since boot, from gyro */
int16_t gyro_raw[3]; /**< Raw sensor values of angular velocity */
- uint16_t gyro_counter; /**< Number of raw measurments taken */
float gyro_rad_s[3]; /**< Angular velocity in radian per seconds */
-
+
int16_t accelerometer_raw[3]; /**< Raw acceleration in NED body frame */
- uint32_t accelerometer_counter; /**< Number of raw acc measurements taken */
float accelerometer_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
int accelerometer_mode; /**< Accelerometer measurement mode */
float accelerometer_range_m_s2; /**< Accelerometer measurement range in m/s^2 */
+ uint64_t accelerometer_timestamp; /**< Accelerometer timestamp */
int16_t magnetometer_raw[3]; /**< Raw magnetic field in NED body frame */
float magnetometer_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
int magnetometer_mode; /**< Magnetometer measurement mode */
float magnetometer_range_ga; /**< ± measurement range in Gauss */
float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */
- uint32_t magnetometer_counter; /**< Number of raw mag measurements taken */
-
+ uint64_t magnetometer_timestamp; /**< Magnetometer timestamp */
+
float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */
float baro_alt_meter; /**< Altitude, already temp. comp. */
float baro_temp_celcius; /**< Temperature in degrees celsius */
float adc_voltage_v[4]; /**< ADC voltages of ADC Chan 10/11/12/13 or -1 */
float mcu_temp_celcius; /**< Internal temperature measurement of MCU */
- uint32_t baro_counter; /**< Number of raw baro measurements taken */
+ uint64_t baro_timestamp; /**< Barometer timestamp */
- float differential_pressure_pa; /**< Airspeed sensor differential pressure */
- uint32_t differential_pressure_counter; /**< Number of raw differential pressure measurements taken */
+ float differential_pressure_pa; /**< Airspeed sensor differential pressure */
+ uint64_t differential_pressure_timestamp; /**< Last measurement timestamp */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h
index e5a35ff9b..40328af14 100755
--- a/src/modules/uORB/topics/vehicle_attitude.h
+++ b/src/modules/uORB/topics/vehicle_attitude.h
@@ -76,7 +76,7 @@ struct vehicle_attitude_s {
float rate_offsets[3]; /**< Offsets of the body angular rates from zero */
float R[3][3]; /**< Rotation matrix body to world, (Tait-Bryan, NED) */
float q[4]; /**< Quaternion (NED) */
- float g_comp[3]; /**< Compensated gravity vector */
+ float g_comp[3]; /**< Compensated gravity vector */
bool R_valid; /**< Rotation matrix valid */
bool q_valid; /**< Quaternion valid */