mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
GCS_MAVLink: send temperature for IMUs
This commit is contained in:
parent
04827d229c
commit
595a49eec4
@ -209,7 +209,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;
|
||||
|
@ -1594,10 +1594,11 @@ void GCS_MAVLINK::send_raw_imu()
|
||||
gyro.z * 1000.0f,
|
||||
mag.x,
|
||||
mag.y,
|
||||
mag.z);
|
||||
mag.z, 0,
|
||||
ins.get_temperature(0)*100);
|
||||
}
|
||||
|
||||
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();
|
||||
@ -1632,7 +1633,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,
|
||||
ins.get_temperature(instance));
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user