sensor messages remove unused fields and improve comments

This commit is contained in:
Daniel Agar 2018-07-29 12:22:29 -04:00 committed by Lorenz Meier
parent fc8a05f636
commit cc96e5ec5e
33 changed files with 57 additions and 128 deletions

View File

@ -1,18 +1,19 @@
uint64 integral_dt # integration time
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 error_count
float32 x # acceleration in the NED X board axis in m/s^2
float32 y # acceleration in the NED Y board axis in m/s^2
float32 z # acceleration in the NED Z board axis in m/s^2
float32 x_integral # velocity in the NED X board axis in m/s over the integration time frame
float32 y_integral # velocity in the NED Y board axis in m/s over the integration time frame
float32 z_integral # velocity in the NED Z board axis in m/s over the integration time frame
float32 temperature # temperature in degrees celsius
float32 range_m_s2 # range in m/s^2 (+- this value)
float32 scaling
uint32 integral_dt # integration time (microseconds)
float32 x_integral # delta velocity in the NED X board axis in m/s over the integration time frame (integral_dt)
float32 y_integral # delta velocity in the NED Y board axis in m/s over the integration time frame (integral_dt)
float32 z_integral # delta velocity in the NED Z board axis in m/s over the integration time frame (integral_dt)
float32 temperature # temperature in degrees celsius
float32 scaling # scaling from raw to m/s^s
int16 x_raw
int16 y_raw
int16 z_raw
int16 temperature_raw
uint32 device_id # unique device ID for the sensor that does not change between power cycles

View File

@ -1,4 +1,7 @@
float32 pressure # static pressure measurement in millibar
float32 temperature # static temperature measurement in deg C
uint64 error_count
uint32 device_id # Sensor ID that must be unique for each baro sensor and must not change
uint64 error_count
float32 pressure # static pressure measurement in millibar
float32 temperature # static temperature measurement in deg C

View File

@ -1,18 +1,19 @@
uint64 integral_dt # integration time
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 error_count
float32 x # angular velocity in the NED X board axis in rad/s
float32 y # angular velocity in the NED Y board axis in rad/s
float32 z # angular velocity in the NED Z board axis in rad/s
float32 x_integral # delta angle in the NED X board axis in rad/s in the integration time frame
float32 y_integral # delta angle in the NED Y board axis in rad/s in the integration time frame
float32 z_integral # delta angle in the NED Z board axis in rad/s in the integration time frame
float32 temperature # temperature in degrees celcius
float32 range_rad_s
float32 scaling
uint32 integral_dt # integration time (microseconds)
float32 x_integral # delta angle in the NED X board axis in rad/s over the integration time frame (integral_dt)
float32 y_integral # delta angle in the NED Y board axis in rad/s over the integration time frame (integral_dt)
float32 z_integral # delta angle in the NED Z board axis in rad/s over the integration time frame (integral_dt)
float32 temperature # temperature in degrees celsius
float32 scaling # scaling from raw to rad/s
int16 x_raw
int16 y_raw
int16 z_raw
int16 temperature_raw
uint32 device_id # unique device ID for the sensor that does not change between power cycles

View File

@ -1,15 +1,16 @@
uint64 error_count
float32 x
float32 y
float32 z
float32 range_ga
float32 scaling
float32 temperature
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 error_count
float32 x # magnetic field in the NED X board axis in Gauss
float32 y # magnetic field in the NED Y board axis in Gauss
float32 z # magnetic field in the NED Z board axis in Gauss
float32 temperature # temperature in degrees celsius
float32 scaling # scaling from raw to Gauss
int16 x_raw
int16 y_raw
int16 z_raw
uint32 device_id # unique device ID for the sensor that does not change between power cycles
bool is_external # if true the mag is external (i.e. not built into the board)
bool is_external # if true the mag is external (i.e. not built into the board)

View File

@ -1458,7 +1458,6 @@ ADIS16448::measure()
}
grb.scaling = _gyro_range_scale * M_PI_F / 180.0f;
grb.range_rad_s = _gyro_range_rad_s;
/* Accel report: */
arb.x_raw = report.accel_x;
@ -1488,7 +1487,6 @@ ADIS16448::measure()
}
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
/* Mag report: */
mrb.x_raw = report.mag_x;
@ -1518,14 +1516,10 @@ ADIS16448::measure()
}
mrb.scaling = _mag_range_scale / 1000.0f;
mrb.range_ga = _mag_range_mgauss / 1000.0f;
/* Temperature report: */
grb.temperature_raw = report.temp;
grb.temperature = (report.temp * 0.07386f) + 31.0f;
arb.temperature_raw = report.temp;
arb.temperature = (report.temp * 0.07386f) + 31.0f;
arb.temperature = grb.temperature;
matrix::Vector3f aval(x_in_new, y_in_new, z_in_new);
matrix::Vector3f aval_integrated;

View File

@ -561,7 +561,6 @@ ADIS16477::publish_accel(const ADISReport &report)
arb.y_raw = report.accel_y;
arb.z_raw = report.accel_z;
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
float xraw_f = report.accel_x * _accel_range_scale;
float yraw_f = report.accel_y * _accel_range_scale;
@ -588,7 +587,6 @@ ADIS16477::publish_accel(const ADISReport &report)
/* Temperature report: */
// temperature 1 LSB = 0.1°C
arb.temperature_raw = report.temp;
arb.temperature = report.temp * 0.1;
if (accel_notify) {
@ -608,7 +606,6 @@ ADIS16477::publish_gyro(const ADISReport &report)
/* Gyro report: */
grb.scaling = math::radians(_gyro_range_scale);
grb.range_rad_s = _gyro_range_rad_s;
grb.x_raw = report.gyro_x;
grb.y_raw = report.gyro_y;
grb.z_raw = report.gyro_z;
@ -639,7 +636,6 @@ ADIS16477::publish_gyro(const ADISReport &report)
/* Temperature report: */
// temperature 1 LSB = 0.1°C
grb.temperature_raw = report.temp;
grb.temperature = report.temp * 0.1f;
if (gyro_notify) {

View File

@ -727,7 +727,6 @@ BMA180::measure()
report.y = ((report.y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
report.z = ((report.z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
report.scaling = _accel_range_scale;
report.range_m_s2 = _accel_range_m_s2;
_reports->force(&report);

View File

@ -779,11 +779,9 @@ BMI055_accel::measure()
arb.z_integral = aval_integrated(2);
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
_last_temperature = 23 + report.temp * 1.0f / 512.0f;
arb.temperature_raw = report.temp;
arb.temperature = _last_temperature;
arb.device_id = _device_id.devid;

View File

@ -755,9 +755,7 @@ BMI055_gyro::measure()
grb.z_integral = gval_integrated(2);
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = report.temp;
grb.temperature = _last_temperature;
grb.device_id = _device_id.devid;

View File

@ -1186,11 +1186,9 @@ BMI160::measure()
arb.z_integral = aval_integrated(2);
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
_last_temperature = 23 + report.temp * 1.0f / 512.0f;
arb.temperature_raw = report.temp;
arb.temperature = _last_temperature;
/* return device ID */
@ -1224,9 +1222,7 @@ BMI160::measure()
grb.z_integral = gval_integrated(2);
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = report.temp;
grb.temperature = _last_temperature;
/* return device ID */

View File

@ -1071,7 +1071,6 @@ FXAS21002C::measure()
gyro_report.z_integral = gval_integrated(2);
gyro_report.scaling = _gyro_range_scale;
gyro_report.range_rad_s = _gyro_range_rad_s;
/* return device ID */
gyro_report.device_id = _device_id.devid;

View File

@ -1469,7 +1469,6 @@ FXOS8701CQ::measure()
accel_report.z_integral = aval_integrated(2);
accel_report.scaling = _accel_range_scale;
accel_report.range_m_s2 = _accel_range_m_s2;
/* return device ID */
accel_report.device_id = _device_id.devid;
@ -1535,7 +1534,6 @@ FXOS8701CQ::mag_measure()
mag_report.y = ((yraw_f * _mag_range_scale) - _mag_scale.y_offset) * _mag_scale.y_scale;
mag_report.z = ((zraw_f * _mag_range_scale) - _mag_scale.z_offset) * _mag_scale.z_scale;
mag_report.scaling = _mag_range_scale;
mag_report.range_ga = (float)_mag_range_ga;
mag_report.error_count = perf_event_count(_bad_registers) + perf_event_count(_bad_values);
mag_report.temperature = _last_temperature;
@ -1818,8 +1816,6 @@ test()
PX4_INFO("accel y: \t%d\traw", (int)accel_report.y_raw);
PX4_INFO("accel z: \t%d\traw", (int)accel_report.z_raw);
PX4_INFO("accel range: %8.4f m/s^2", (double)accel_report.range_m_s2);
/* get the driver */
fd_mag = open(FXOS8701C_DEVICE_PATH_MAG, O_RDONLY);
@ -1850,7 +1846,6 @@ test()
PX4_INFO("mag x: \t%d\traw", (int)m_report.x_raw);
PX4_INFO("mag y: \t%d\traw", (int)m_report.y_raw);
PX4_INFO("mag z: \t%d\traw", (int)m_report.z_raw);
PX4_INFO("mag range: %8.4f ga", (double)m_report.range_ga);
/* reset to default polling */
if (ioctl(fd_accel, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {

View File

@ -1015,8 +1015,6 @@ L3GD20::measure()
report.z_raw = raw_report.z;
report.temperature_raw = raw_report.temp;
float xraw_f = report.x_raw;
float yraw_f = report.y_raw;
float zraw_f = report.z_raw;
@ -1043,7 +1041,6 @@ L3GD20::measure()
report.temperature = L3GD20_TEMP_OFFSET_CELSIUS - raw_report.temp;
report.scaling = _gyro_range_scale;
report.range_rad_s = _gyro_range_rad_s;
/* return device ID */
report.device_id = _device_id.devid;

View File

@ -1577,7 +1577,6 @@ LSM303D::measure()
accel_report.z_integral = aval_integrated(2);
accel_report.scaling = _accel_range_scale;
accel_report.range_m_s2 = _accel_range_m_s2;
/* return device ID */
accel_report.device_id = _device_id.devid;
@ -1658,7 +1657,6 @@ LSM303D::mag_measure()
mag_report.y = ((yraw_f * _mag_range_scale) - _mag_scale.y_offset) * _mag_scale.y_scale;
mag_report.z = ((zraw_f * _mag_range_scale) - _mag_scale.z_offset) * _mag_scale.z_scale;
mag_report.scaling = _mag_range_scale;
mag_report.range_ga = (float)_mag_range_ga;
mag_report.error_count = perf_event_count(_bad_registers) + perf_event_count(_bad_values);
/* remember the temperature. The datasheet isn't clear, but it

View File

@ -1970,6 +1970,7 @@ MPU6000::measure()
/* NOTE: Axes have been swapped to match the board a few lines above. */
arb.scaling = _accel_range_scale;
arb.x_raw = report.accel_x;
arb.y_raw = report.accel_y;
arb.z_raw = report.accel_z;
@ -1997,9 +1998,6 @@ MPU6000::measure()
arb.y_integral = aval_integrated(1);
arb.z_integral = aval_integrated(2);
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
if (is_icm_device()) { // if it is an ICM20608
_last_temperature = (report.temp) / 326.8f + 25.0f;
@ -2007,7 +2005,6 @@ MPU6000::measure()
_last_temperature = (report.temp) / 361.0f + 35.0f;
}
arb.temperature_raw = report.temp;
arb.temperature = _last_temperature;
/* return device ID */
@ -2041,9 +2038,7 @@ MPU6000::measure()
grb.z_integral = gval_integrated(2);
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = report.temp;
grb.temperature = _last_temperature;
/* return device ID */

View File

@ -225,7 +225,6 @@ MPU9250_mag::_measure(struct ak8963_regs data)
mrb.x = ((xraw_f * _mag_range_scale * _mag_asa_x) - _mag_scale.x_offset) * _mag_scale.x_scale;
mrb.y = ((yraw_f * _mag_range_scale * _mag_asa_y) - _mag_scale.y_offset) * _mag_scale.y_scale;
mrb.z = ((zraw_f * _mag_range_scale * _mag_asa_z) - _mag_scale.z_offset) * _mag_scale.z_scale;
mrb.range_ga = 48.0f;
mrb.scaling = _mag_range_scale;
mrb.temperature = _parent->_last_temperature;
mrb.device_id = _parent->_mag->_device_id.devid;

View File

@ -1437,11 +1437,9 @@ MPU9250::measure()
arb.z_integral = aval_integrated(2);
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
_last_temperature = (report.temp) / 361.0f + 35.0f;
arb.temperature_raw = report.temp;
arb.temperature = _last_temperature;
/* return device ID */
@ -1475,9 +1473,7 @@ MPU9250::measure()
grb.z_integral = gval_integrated(2);
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = report.temp;
grb.temperature = _last_temperature;
/* return device ID */

View File

@ -891,7 +891,6 @@ HMC5883::collect()
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
new_report.timestamp = hrt_absolute_time();
new_report.error_count = perf_event_count(_comms_errors);
new_report.range_ga = _range_ga;
new_report.scaling = _range_scale;
new_report.device_id = _device_id.devid;

View File

@ -891,7 +891,6 @@ IST8310::collect()
new_report.timestamp = hrt_absolute_time();
new_report.is_external = sensor_is_external;
new_report.error_count = perf_event_count(_comms_errors);
new_report.range_ga = 1.6f; // constant for this sensor for x and y
new_report.scaling = _range_scale;
new_report.device_id = _device_id.devid;

View File

@ -372,7 +372,6 @@ LIS3MDL::collect()
new_mag_report.timestamp = hrt_absolute_time();
new_mag_report.error_count = perf_event_count(_comms_errors);
new_mag_report.range_ga = _range_ga;
new_mag_report.scaling = _range_scale;
new_mag_report.device_id = _device_id.devid;

View File

@ -479,7 +479,6 @@ LSM303AGR::collect()
mag_report.y = ((yraw_f * _mag_range_scale) - _mag_scale.y_offset) * _mag_scale.y_scale;
mag_report.z = ((zraw_f * _mag_range_scale) - _mag_scale.z_offset) * _mag_scale.z_scale;
mag_report.scaling = _mag_range_scale;
mag_report.range_ga = _mag_range_ga;
mag_report.error_count = perf_event_count(_bad_registers) + perf_event_count(_bad_values);
/* remember the temperature. The datasheet isn't clear, but it

View File

@ -51,7 +51,7 @@ Integrator::Integrator(uint64_t auto_reset_interval, bool coning_compensation) :
}
bool
Integrator::put(uint64_t timestamp, matrix::Vector3f &val, matrix::Vector3f &integral, uint64_t &integral_dt)
Integrator::put(uint64_t timestamp, matrix::Vector3f &val, matrix::Vector3f &integral, uint32_t &integral_dt)
{
if (_last_integration_time == 0) {
/* this is the first item in the integrator */
@ -115,7 +115,7 @@ Integrator::put(uint64_t timestamp, matrix::Vector3f &val, matrix::Vector3f &int
bool
Integrator::put_with_interval(unsigned interval_us, matrix::Vector3f &val, matrix::Vector3f &integral,
uint64_t &integral_dt)
uint32_t &integral_dt)
{
if (_last_integration_time == 0) {
/* this is the first item in the integrator */
@ -134,7 +134,7 @@ Integrator::put_with_interval(unsigned interval_us, matrix::Vector3f &val, matri
}
matrix::Vector3f
Integrator::get(bool reset, uint64_t &integral_dt)
Integrator::get(bool reset, uint32_t &integral_dt)
{
matrix::Vector3f val = _alpha;
@ -146,7 +146,7 @@ Integrator::get(bool reset, uint64_t &integral_dt)
}
matrix::Vector3f
Integrator::get_and_filtered(bool reset, uint64_t &integral_dt, matrix::Vector3f &filtered_val)
Integrator::get_and_filtered(bool reset, uint32_t &integral_dt, matrix::Vector3f &filtered_val)
{
// Do the usual get with reset first but don't return yet.
matrix::Vector3f ret_integral = get(reset, integral_dt);
@ -160,18 +160,13 @@ Integrator::get_and_filtered(bool reset, uint64_t &integral_dt, matrix::Vector3f
}
void
Integrator::_reset(uint64_t &integral_dt)
Integrator::_reset(uint32_t &integral_dt)
{
_alpha(0) = 0.0f;
_alpha(1) = 0.0f;
_alpha(2) = 0.0f;
_last_alpha(0) = 0.0f;
_last_alpha(1) = 0.0f;
_last_alpha(2) = 0.0f;
_beta(0) = 0.0f;
_beta(1) = 0.0f;
_beta(2) = 0.0f;
_alpha.zero();
_last_alpha.zero();
_beta.zero();
integral_dt = (_last_integration_time - _last_reset_time);
_last_reset_time = _last_integration_time;
}

View File

@ -67,7 +67,7 @@ public:
* @return true if putting the item triggered an integral reset and the integral should be
* published.
*/
bool put(uint64_t timestamp, matrix::Vector3f &val, matrix::Vector3f &integral, uint64_t &integral_dt);
bool put(uint64_t timestamp, matrix::Vector3f &val, matrix::Vector3f &integral, uint32_t &integral_dt);
/**
* Put an item into the integral but provide an interval instead of a timestamp.
@ -81,8 +81,7 @@ public:
* @return true if putting the item triggered an integral reset and the integral should be
* published.
*/
bool put_with_interval(unsigned interval_us, matrix::Vector3f &val, matrix::Vector3f &integral,
uint64_t &integral_dt);
bool put_with_interval(unsigned interval_us, matrix::Vector3f &val, matrix::Vector3f &integral, uint32_t &integral_dt);
/**
* Get the current integral and reset the integrator if needed.
@ -91,7 +90,7 @@ public:
* @param integral_dt Get the dt in us of the current integration (only if reset).
* @return the integral since the last read-reset
*/
matrix::Vector3f get(bool reset, uint64_t &integral_dt);
matrix::Vector3f get(bool reset, uint32_t &integral_dt);
/**
@ -103,7 +102,7 @@ public:
* @param filtered_val The integral differentiated by the integration time.
* @return the integral since the last read-reset
*/
matrix::Vector3f get_and_filtered(bool reset, uint64_t &integral_dt, matrix::Vector3f &filtered_val);
matrix::Vector3f get_and_filtered(bool reset, uint32_t &integral_dt, matrix::Vector3f &filtered_val);
/**
@ -132,5 +131,5 @@ private:
*
* @param integral_dt Get the dt in us of the current integration.
*/
void _reset(uint64_t &integral_dt);
void _reset(uint32_t &integral_dt);
};

View File

@ -861,7 +861,6 @@ ACCELSIM::_measure()
accel_report.z = raw_accel_report.z;
accel_report.scaling = _accel_range_scale;
accel_report.range_m_s2 = _accel_range_m_s2;
_accel_reports->force(&accel_report);

View File

@ -1033,11 +1033,9 @@ GYROSIM::_measure()
arb.z_raw = (int16_t)(mpu_report.accel_z / _accel_range_scale);
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
_last_temperature = mpu_report.temp;
arb.temperature_raw = (int16_t)((mpu_report.temp - 35.0f) * 361.0f);
arb.temperature = _last_temperature;
arb.x = mpu_report.accel_x;
@ -1060,9 +1058,7 @@ GYROSIM::_measure()
grb.z_raw = (int16_t)(mpu_report.gyro_z / _gyro_range_scale);
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = (int16_t)((mpu_report.temp - 35.0f) * 361.0f);
grb.temperature = _last_temperature;
grb.x = mpu_report.gyro_x;
@ -1322,8 +1318,6 @@ test()
PX4_INFO("acc x: \t%d\traw 0x%0x", (short)a_report.x_raw, (unsigned short)a_report.x_raw);
PX4_INFO("acc y: \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
PX4_INFO("acc z: \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
PX4_INFO("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
(double)(a_report.range_m_s2 / CONSTANTS_ONE_G));
/* do a simple demand read */
sz = h_gyro.read(&g_report, sizeof(g_report));
@ -1340,11 +1334,8 @@ test()
PX4_INFO("gyro x: \t%d\traw", (int)g_report.x_raw);
PX4_INFO("gyro y: \t%d\traw", (int)g_report.y_raw);
PX4_INFO("gyro z: \t%d\traw", (int)g_report.z_raw);
PX4_INFO("gyro range: %8.4f rad/s (%d deg/s)", (double)g_report.range_rad_s,
(int)((g_report.range_rad_s / M_PI_F) * 180.0f + 0.5f));
PX4_INFO("temp: \t%8.4f\tdeg celsius", (double)a_report.temperature);
PX4_INFO("temp: \t%d\traw 0x%0x", (short)a_report.temperature_raw, (unsigned short)a_report.temperature_raw);
/* XXX add poll-rate tests here too */

View File

@ -145,7 +145,6 @@ void UavcanMagnetometerBridge::mag_sub_cb(const
&msg)
{
lock();
_report.range_ga = 1.3F; // Arbitrary number, doesn't really mean anything
/*
* FIXME HACK
* This code used to rely on msg.getMonotonicTimestamp().toUSec() instead of HRT.

View File

@ -297,7 +297,6 @@ int DfAK8963Wrapper::_publish(struct mag_sensor_data &data)
// TODO: get these right
//mag_report.scaling = -1.0f;
//mag_report.range_m_s2 = -1.0f;
mag_report.device_id = m_id.dev_id;

View File

@ -297,7 +297,6 @@ int DfHmc5883Wrapper::_publish(struct mag_sensor_data &data)
// TODO: get these right
//mag_report.scaling = -1.0f;
//mag_report.range_m_s2 = -1.0f;
mag_report.device_id = m_id.dev_id;

View File

@ -570,7 +570,7 @@ int DfLsm9ds1Wrapper::_publish(struct imu_sensor_data &data)
}
matrix::Vector3f vec_integrated_unused;
uint64_t integral_dt_unused;
uint32_t integral_dt_unused;
matrix::Vector3f accel_val(data.accel_m_s2_x,
data.accel_m_s2_y,
data.accel_m_s2_z);
@ -628,16 +628,13 @@ int DfLsm9ds1Wrapper::_publish(struct imu_sensor_data &data)
// TODO: get these right
gyro_report.scaling = -1.0f;
gyro_report.range_rad_s = -1.0f;
gyro_report.device_id = m_id.dev_id;
accel_report.scaling = -1.0f;
accel_report.range_m_s2 = -1.0f;
accel_report.device_id = m_id.dev_id;
if (_mag_enabled) {
mag_report.scaling = -1.0f;
mag_report.range_ga = -1.0f;
mag_report.device_id = m_id.dev_id;
}

View File

@ -432,7 +432,7 @@ int DfMPU6050Wrapper::_publish(struct imu_sensor_data &data)
uint64_t now = hrt_absolute_time();
matrix::Vector3f vec_integrated_unused;
uint64_t integral_dt_unused;
uint32_t integral_dt_unused;
matrix::Vector3f accel_val(data.accel_m_s2_x, data.accel_m_s2_y, data.accel_m_s2_z);
@ -495,11 +495,9 @@ int DfMPU6050Wrapper::_publish(struct imu_sensor_data &data)
// TODO: get these right
gyro_report.scaling = -1.0f;
gyro_report.range_rad_s = -1.0f;
gyro_report.device_id = m_id.dev_id;
accel_report.scaling = -1.0f;
accel_report.range_m_s2 = -1.0f;
accel_report.device_id = m_id.dev_id;
// TODO: remove these (or get the values)

View File

@ -706,11 +706,9 @@ int DfMpu9250Wrapper::_publish(struct imu_sensor_data &data)
// TODO: get these right
gyro_report.scaling = -1.0f;
gyro_report.range_rad_s = -1.0f;
gyro_report.device_id = m_id.dev_id;
accel_report.scaling = -1.0f;
accel_report.range_m_s2 = -1.0f;
accel_report.device_id = m_id.dev_id;
if (_mag_enabled) {
@ -718,7 +716,6 @@ int DfMpu9250Wrapper::_publish(struct imu_sensor_data &data)
mag_report.is_external = false;
mag_report.scaling = -1.0f;
mag_report.range_ga = -1.0f;
mag_report.device_id = m_id.dev_id;
xraw_f = data.mag_ga_x;

View File

@ -405,31 +405,26 @@ void update_reports()
_gyro.y = ((_data.gyro_raw[1] * _data.gyro_scaling) - _gyro_sc.y_offset) * _gyro_sc.y_scale;
_gyro.z = ((_data.gyro_raw[2] * _data.gyro_scaling) - _gyro_sc.z_offset) * _gyro_sc.z_scale;
_gyro.temperature = _data.temperature;
_gyro.range_rad_s = _data.gyro_range_rad_s;
_gyro.scaling = _data.gyro_scaling;
_gyro.x_raw = _data.gyro_raw[0];
_gyro.y_raw = _data.gyro_raw[1];
_gyro.z_raw = _data.gyro_raw[2];
_gyro.temperature_raw = _data.temperature_raw;
_accel.timestamp = _data.timestamp;
_accel.x = ((_data.accel_raw[0] * _data.accel_scaling) - _accel_sc.x_offset) * _accel_sc.x_scale;
_accel.y = ((_data.accel_raw[1] * _data.accel_scaling) - _accel_sc.y_offset) * _accel_sc.y_scale;
_accel.z = ((_data.accel_raw[2] * _data.accel_scaling) - _accel_sc.z_offset) * _accel_sc.z_scale;
_accel.temperature = _data.temperature;
_accel.range_m_s2 = _data.accel_range_m_s2;
_accel.scaling = _data.accel_scaling;
_accel.x_raw = _data.accel_raw[0];
_accel.y_raw = _data.accel_raw[1];
_accel.z_raw = _data.accel_raw[2];
_accel.temperature_raw = _data.temperature_raw;
if (_data.mag_data_ready) {
_mag.timestamp = _data.timestamp;
_mag.x = ((_data.mag_raw[0] * _data.mag_scaling) - _mag_sc.x_offset) * _mag_sc.x_scale;
_mag.y = ((_data.mag_raw[1] * _data.mag_scaling) - _mag_sc.y_offset) * _mag_sc.y_scale;
_mag.z = ((_data.mag_raw[2] * _data.mag_scaling) - _mag_sc.z_offset) * _mag_sc.z_scale;
_mag.range_ga = _data.mag_range_ga;
_mag.scaling = _data.mag_scaling;
_mag.temperature = _data.temperature;
_mag.x_raw = _data.mag_raw[0];

View File

@ -126,7 +126,6 @@ void MicroBenchORB::reset()
lpos.dist_bottom_valid = rand();
gyro.timestamp = rand();
gyro.temperature_raw = rand();
}
ut_declare_test_c(test_microbench_uorb, MicroBenchORB)