Browse Source

MAVLink: Update to new sensors combined topic

sbg
Lorenz Meier 10 years ago
parent
commit
caacb4f777
  1. 24
      src/modules/mavlink/mavlink_messages.cpp
  2. 32
      src/modules/mavlink/mavlink_receiver.cpp

24
src/modules/mavlink/mavlink_messages.cpp

@ -643,28 +643,28 @@ protected: @@ -643,28 +643,28 @@ protected:
if (_sensor_sub->update(&_sensor_time, &sensor)) {
uint16_t fields_updated = 0;
if (_accel_timestamp != sensor.accelerometer_timestamp) {
if (_accel_timestamp != sensor.accelerometer_timestamp[0]) {
/* mark first three dimensions as changed */
fields_updated |= (1 << 0) | (1 << 1) | (1 << 2);
_accel_timestamp = sensor.accelerometer_timestamp;
_accel_timestamp = sensor.accelerometer_timestamp[0];
}
if (_gyro_timestamp != sensor.timestamp) {
if (_gyro_timestamp != sensor.gyro_timestamp[0]) {
/* mark second group dimensions as changed */
fields_updated |= (1 << 3) | (1 << 4) | (1 << 5);
_gyro_timestamp = sensor.timestamp;
_gyro_timestamp = sensor.gyro_timestamp[0];
}
if (_mag_timestamp != sensor.magnetometer_timestamp) {
if (_mag_timestamp != sensor.magnetometer_timestamp[0]) {
/* mark third group dimensions as changed */
fields_updated |= (1 << 6) | (1 << 7) | (1 << 8);
_mag_timestamp = sensor.magnetometer_timestamp;
_mag_timestamp = sensor.magnetometer_timestamp[0];
}
if (_baro_timestamp != sensor.baro_timestamp) {
if (_baro_timestamp != sensor.baro_timestamp[0]) {
/* mark last group dimensions as changed */
fields_updated |= (1 << 9) | (1 << 11) | (1 << 12);
_baro_timestamp = sensor.baro_timestamp;
_baro_timestamp = sensor.baro_timestamp[0];
}
mavlink_highres_imu_t msg;
@ -679,10 +679,10 @@ protected: @@ -679,10 +679,10 @@ protected:
msg.xmag = sensor.magnetometer_ga[0];
msg.ymag = sensor.magnetometer_ga[1];
msg.zmag = sensor.magnetometer_ga[2];
msg.abs_pressure = sensor.baro_pres_mbar;
msg.diff_pressure = sensor.differential_pressure_pa;
msg.pressure_alt = sensor.baro_alt_meter;
msg.temperature = sensor.baro_temp_celcius;
msg.abs_pressure = sensor.baro_pres_mbar[0];
msg.diff_pressure = sensor.differential_pressure_pa[0];
msg.pressure_alt = sensor.baro_alt_meter[0];
msg.temperature = sensor.baro_temp_celcius[0];
msg.fields_updated = fields_updated;
_mavlink->send_message(MAVLINK_MSG_ID_HIGHRES_IMU, &msg);

32
src/modules/mavlink/mavlink_receiver.cpp

@ -1433,9 +1433,9 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) @@ -1433,9 +1433,9 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
hil_sensors.accelerometer_m_s2[0] = imu.xacc;
hil_sensors.accelerometer_m_s2[1] = imu.yacc;
hil_sensors.accelerometer_m_s2[2] = imu.zacc;
hil_sensors.accelerometer_mode = 0; // TODO what is this?
hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16
hil_sensors.accelerometer_timestamp = timestamp;
hil_sensors.accelerometer_mode[0] = 0; // TODO what is this?
hil_sensors.accelerometer_range_m_s2[0] = 32.7f; // int16
hil_sensors.accelerometer_timestamp[0] = timestamp;
hil_sensors.adc_voltage_v[0] = 0.0f;
hil_sensors.adc_voltage_v[1] = 0.0f;
@ -1447,19 +1447,19 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) @@ -1447,19 +1447,19 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
hil_sensors.magnetometer_ga[0] = imu.xmag;
hil_sensors.magnetometer_ga[1] = imu.ymag;
hil_sensors.magnetometer_ga[2] = imu.zmag;
hil_sensors.magnetometer_range_ga = 32.7f; // int16
hil_sensors.magnetometer_mode = 0; // TODO what is this
hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;
hil_sensors.magnetometer_timestamp = timestamp;
hil_sensors.baro_pres_mbar = imu.abs_pressure;
hil_sensors.baro_alt_meter = imu.pressure_alt;
hil_sensors.baro_temp_celcius = imu.temperature;
hil_sensors.baro_timestamp = timestamp;
hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa
hil_sensors.differential_pressure_filtered_pa = hil_sensors.differential_pressure_pa;
hil_sensors.differential_pressure_timestamp = timestamp;
hil_sensors.magnetometer_range_ga[0] = 32.7f; // int16
hil_sensors.magnetometer_mode[0] = 0; // TODO what is this
hil_sensors.magnetometer_cuttoff_freq_hz[0] = 50.0f;
hil_sensors.magnetometer_timestamp[0] = timestamp;
hil_sensors.baro_pres_mbar[0] = imu.abs_pressure;
hil_sensors.baro_alt_meter[0] = imu.pressure_alt;
hil_sensors.baro_temp_celcius[0] = imu.temperature;
hil_sensors.baro_timestamp[0] = timestamp;
hil_sensors.differential_pressure_pa[0] = imu.diff_pressure * 1e2f; //from hPa to Pa
hil_sensors.differential_pressure_filtered_pa[0] = hil_sensors.differential_pressure_pa[0];
hil_sensors.differential_pressure_timestamp[0] = timestamp;
/* publish combined sensor topic */
if (_sensors_pub == nullptr) {

Loading…
Cancel
Save