GCS_MAVLink: updates to support the latest stable mavlink changes (IMU temperature extension)

This commit is contained in:
Do Carmo Lucas 2019-10-02 20:57:50 +01:00 committed by Andrew Tridgell
parent fbeb5a8082
commit dc4ad26e96
2 changed files with 7 additions and 4 deletions

View File

@ -210,7 +210,7 @@ public:
virtual void send_position_target_local_ned() { };
void send_servo_output_raw();
void send_accelcal_vehicle_position(uint32_t position);
void send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag));
void send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature));
void send_sys_status();
void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc);
void send_rpm() const;

View File

@ -1601,10 +1601,12 @@ void GCS_MAVLINK::send_raw_imu()
gyro.z * 1000.0f,
mag.x,
mag.y,
mag.z);
mag.z,
0, // for now, only instance 0 is sent
0); // TODO: get the IMU temperature
}
void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag))
void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature))
{
const AP_InertialSensor &ins = AP::ins();
const Compass &compass = AP::compass();
@ -1639,7 +1641,8 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan
gyro.z * 1000.0f,
mag.x,
mag.y,
mag.z);
mag.z,
0); // TODO: get the IMU temperature
}