From cd05dfcc7cb557575e62f5f93ddd3a86c073d517 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 12:58:17 +0100 Subject: Moved to sensor_combined topic for estimator --- .../fw_att_pos_estimator_main.cpp | 148 ++++++++++++++++++--- 1 file changed, 129 insertions(+), 19 deletions(-) (limited to 'src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp') diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp index e6747604b..466f6d51f 100644 --- a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp +++ b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp @@ -50,9 +50,17 @@ #include #include #include + +#define SENSOR_COMBINED_SUB + + #include #include #include +#include +#ifdef SENSOR_COMBINED_SUB +#include +#endif #include #include #include @@ -60,14 +68,9 @@ #include #include #include -#include -#include #include -#include -#include #include #include -#include #include #include #include @@ -77,6 +80,8 @@ #include "../../../InertialNav/code/estimator.h" + + /** * estimator app start / stop handling function * @@ -118,12 +123,15 @@ private: bool _task_should_exit; /**< if true, sensor task should exit */ int _estimator_task; /**< task handle for sensor task */ - +#ifndef SENSOR_COMBINED_SUB int _gyro_sub; /**< gyro sensor subscription */ int _accel_sub; /**< accel sensor subscription */ int _mag_sub; /**< mag sensor subscription */ - int _attitude_sub; /**< raw rc channels data subscription */ + #else + int _sensor_combined_sub; + #endif int _airspeed_sub; /**< airspeed subscription */ + int _baro_sub; /**< barometer subscription */ int _gps_sub; /**< GPS subscription */ int _vstatus_sub; /**< vehicle status subscription */ int _params_sub; /**< notification of parameter updates */ @@ -135,12 +143,11 @@ private: orb_advert_t _local_pos_pub; /**< position in local frame */ struct vehicle_attitude_s _att; /**< vehicle attitude */ - struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */ - struct manual_control_setpoint_s _manual; /**< r/c channel data */ struct gyro_report _gyro; struct accel_report _accel; struct mag_report _mag; struct airspeed_s _airspeed; /**< airspeed */ + struct baro_report _baro; /**< baro readings */ struct vehicle_status_s _vstatus; /**< vehicle status */ struct vehicle_global_position_s _global_pos; /**< global vehicle position */ struct vehicle_local_position_s _local_pos; /**< local vehicle position */ @@ -150,6 +157,10 @@ private: struct accel_scale _accel_offsets; struct mag_scale _mag_offsets; +#ifdef SENSOR_COMBINED_SUB + struct sensor_combined_s _sensor_combined; +#endif + perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _perf_gyro; /// 1.0f) + deltaT = 0.01f; + + // Always store data, independent of init status + /* fill in last data set */ + dtIMU = deltaT; + + angRate.x = _sensor_combined.gyro_rad_s[0]; + angRate.y = _sensor_combined.gyro_rad_s[1]; + angRate.z = _sensor_combined.gyro_rad_s[2]; + + accel.x = _sensor_combined.accelerometer_m_s2[0]; + accel.y = _sensor_combined.accelerometer_m_s2[1]; + accel.z = _sensor_combined.accelerometer_m_s2[2]; + + dAngIMU = 0.5f * (angRate + lastAngRate) * dtIMU; + lastAngRate = angRate; + dVelIMU = 0.5f * (accel + lastAccel) * dtIMU; + lastAccel = accel; + + if (last_mag != _sensor_combined.magnetometer_timestamp) { + mag_updated = true; + } + last_mag = _sensor_combined.magnetometer_timestamp; + + #endif + if (_initialized) { /* predict states and covariances */ @@ -490,6 +572,14 @@ FixedwingEstimator::task_main() } } + bool baro_updated; + orb_check(_baro_sub, &baro_updated); + if (baro_updated) { + orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro); + + /* XXX leverage baro */ + } + bool gps_updated; orb_check(_gps_sub, &gps_updated); if (gps_updated) { @@ -554,12 +644,16 @@ FixedwingEstimator::task_main() fuseHgtData = false; } - bool mag_updated; + #ifndef SENSOR_COMBINED_SUB orb_check(_mag_sub, &mag_updated); + #endif if (mag_updated) { - orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag); + perf_count(_perf_mag); + #ifndef SENSOR_COMBINED_SUB + orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag); + // XXX we compensate the offsets upfront - should be close to zero. // XXX the purpose of the 0.001 factor is unclear // 0.001f @@ -571,6 +665,22 @@ FixedwingEstimator::task_main() magData.z = 0.001f * _mag.z; magBias.z = 0.0f; // _mag_offsets.y_offset + + #else + + // XXX we compensate the offsets upfront - should be close to zero. + // XXX the purpose of the 0.001 factor is unclear + // 0.001f + magData.x = 0.001f * _sensor_combined.magnetometer_ga[0]; + magBias.x = 0.0f; // _mag_offsets.x_offset + + magData.y = 0.001f * _sensor_combined.magnetometer_ga[1]; + magBias.y = 0.0f; // _mag_offsets.y_offset + + magData.z = 0.001f * _sensor_combined.magnetometer_ga[2]; + magBias.z = 0.0f; // _mag_offsets.y_offset + + #endif if (_initialized) { -- cgit v1.2.3