Skip to content

Commit

Permalink
GCS_MAVLink: support HIGHRES_IMU
Browse files Browse the repository at this point in the history
  • Loading branch information
KoehlerT committed May 7, 2024
1 parent c9f4c47 commit 5f796f3
Show file tree
Hide file tree
Showing 3 changed files with 58 additions and 0 deletions.
1 change: 1 addition & 0 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -354,6 +354,7 @@ class GCS_MAVLINK
void send_rc_channels() const;
void send_rc_channels_raw() const;
void send_raw_imu();
void send_highres_imu();

void send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff));
void send_scaled_pressure();
Expand Down
56 changes: 56 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1005,6 +1005,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_SCALED_IMU, MSG_SCALED_IMU},
{ MAVLINK_MSG_ID_SCALED_IMU2, MSG_SCALED_IMU2},
{ MAVLINK_MSG_ID_SCALED_IMU3, MSG_SCALED_IMU3},
{ MAVLINK_MSG_ID_HIGHRES_IMU, MSG_HIGHRES_IMU},
{ MAVLINK_MSG_ID_SCALED_PRESSURE, MSG_SCALED_PRESSURE},
{ MAVLINK_MSG_ID_SCALED_PRESSURE2, MSG_SCALED_PRESSURE2},
{ MAVLINK_MSG_ID_SCALED_PRESSURE3, MSG_SCALED_PRESSURE3},
Expand Down Expand Up @@ -2127,6 +2128,57 @@ void GCS_MAVLINK::send_raw_imu()
#endif
}

void GCS_MAVLINK::send_highres_imu()
{
Vector3f accel;
Vector3f gyro;
#if AP_INERTIALSENSOR_ENABLED
const AP_InertialSensor &ins = AP::ins();
accel = ins.get_accel(0);
gyro = ins.get_gyro(0);
#endif

Vector3f mag;
#if AP_COMPASS_ENABLED
const Compass &compass = AP::compass();
if (compass.get_count() >= 1) {
mag = compass.get_field(0) * 1000.0f; // convert to gauss
}
#endif

float press_abs = 0.0f;
float temperature = 0.0f;
float altitude = 0.0f;
float diff_pressure = 0.0f;
#if AP_BARO_ENABLED
const AP_Baro &barometer = AP::baro();
press_abs = barometer.get_pressure() * 0.01f;
temperature = barometer.get_temperature();
altitude = barometer.get_altitude();
diff_pressure = press_abs - barometer.get_ground_pressure() * 0.01f;
#endif

mavlink_msg_highres_imu_send(
chan,
AP_HAL::micros64(),
accel.x,
accel.y,
accel.z,
gyro.x,
gyro.y,
gyro.z,
mag.x,
mag.y,
mag.z,
press_abs,
diff_pressure,
altitude,
temperature,
0x3f,
0
);
}

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))
{
#if AP_INERTIALSENSOR_ENABLED
Expand Down Expand Up @@ -6180,6 +6232,10 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
CHECK_PAYLOAD_SIZE(SCALED_IMU3);
send_scaled_imu(2, mavlink_msg_scaled_imu3_send);
break;
case MSG_HIGHRES_IMU:
CHECK_PAYLOAD_SIZE(HIGHRES_IMU);
send_highres_imu();
break;

case MSG_SCALED_PRESSURE:
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
Expand Down
1 change: 1 addition & 0 deletions libraries/GCS_MAVLink/ap_message.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,5 +94,6 @@ enum ap_message : uint8_t {
MSG_HYGROMETER,
MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE,
MSG_RELAY_STATUS,
MSG_HIGHRES_IMU,
MSG_LAST // MSG_LAST must be the last entry in this enum
};

0 comments on commit 5f796f3

Please sign in to comment.