From c5a765758cc5cbfac00c8161fb4484f7beff5cc0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 13 Jul 2014 15:31:34 +1000 Subject: [PATCH] Plane: update for new API --- ArduPlane/GCS_Mavlink.pde | 104 ++------------------------------------ 1 file changed, 4 insertions(+), 100 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index fe54635c03..d8d5363047 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -375,102 +375,6 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan) barometer.get_climb_rate()); } -static void NOINLINE send_raw_imu1(mavlink_channel_t chan) -{ - const Vector3f &accel = ins.get_accel(); - const Vector3f &gyro = ins.get_gyro(); - const Vector3f &mag = compass.get_field(); - - mavlink_msg_raw_imu_send( - chan, - micros(), - accel.x * 1000.0f / GRAVITY_MSS, - accel.y * 1000.0f / GRAVITY_MSS, - accel.z * 1000.0f / GRAVITY_MSS, - gyro.x * 1000.0f, - gyro.y * 1000.0f, - gyro.z * 1000.0f, - mag.x, - mag.y, - mag.z); - - if (ins.get_gyro_count() <= 1 && - ins.get_accel_count() <= 1 && - compass.get_count() <= 1) { - return; - } - const Vector3f &accel2 = ins.get_accel(1); - const Vector3f &gyro2 = ins.get_gyro(1); - const Vector3f &mag2 = compass.get_field(1); - mavlink_msg_scaled_imu2_send( - chan, - millis(), - accel2.x * 1000.0f / GRAVITY_MSS, - accel2.y * 1000.0f / GRAVITY_MSS, - accel2.z * 1000.0f / GRAVITY_MSS, - gyro2.x * 1000.0f, - gyro2.y * 1000.0f, - gyro2.z * 1000.0f, - mag2.x, - mag2.y, - mag2.z); -} - -static void NOINLINE send_raw_imu2(mavlink_channel_t chan) -{ - float pressure = barometer.get_pressure(); - mavlink_msg_scaled_pressure_send( - chan, - millis(), - pressure*0.01f, // hectopascal - (pressure - barometer.get_ground_pressure())*0.01f, // hectopascal - barometer.get_temperature()*100); // 0.01 degrees C -} - -static void NOINLINE send_raw_imu3(mavlink_channel_t chan) -{ - // run this message at a much lower rate - otherwise it - // pointlessly wastes quite a lot of bandwidth - static uint8_t counter; - if (counter++ < 10) { - return; - } - counter = 0; - - Vector3f mag_offsets = compass.get_offsets(); - Vector3f accel_offsets = ins.get_accel_offsets(); - Vector3f gyro_offsets = ins.get_gyro_offsets(); - - mavlink_msg_sensor_offsets_send(chan, - mag_offsets.x, - mag_offsets.y, - mag_offsets.z, - compass.get_declination(), - barometer.get_pressure(), - barometer.get_temperature()*100, - gyro_offsets.x, - gyro_offsets.y, - gyro_offsets.z, - accel_offsets.x, - accel_offsets.y, - accel_offsets.z); -} - -static void NOINLINE send_ahrs(mavlink_channel_t chan) -{ - const Vector3f &omega_I = ahrs.get_gyro_drift(); - mavlink_msg_ahrs_send( - chan, - omega_I.x, - omega_I.y, - omega_I.z, - 0, - 0, - ahrs.get_error_rp(), - ahrs.get_error_yaw()); -} - - #if HIL_MODE != HIL_MODE_DISABLED /* keep last HIL_STATE message to allow sending SIM_STATE @@ -648,17 +552,17 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) case MSG_RAW_IMU1: CHECK_PAYLOAD_SIZE(RAW_IMU); - send_raw_imu1(chan); + gcs[chan-MAVLINK_COMM_0].send_raw_imu(ins, compass); break; case MSG_RAW_IMU2: CHECK_PAYLOAD_SIZE(SCALED_PRESSURE); - send_raw_imu2(chan); + gcs[chan-MAVLINK_COMM_0].send_scaled_pressure(barometer); break; case MSG_RAW_IMU3: CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS); - send_raw_imu3(chan); + gcs[chan-MAVLINK_COMM_0].send_sensor_offsets(ins, compass, barometer); break; case MSG_CURRENT_WAYPOINT: @@ -690,7 +594,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) case MSG_AHRS: CHECK_PAYLOAD_SIZE(AHRS); - send_ahrs(chan); + gcs[chan-MAVLINK_COMM_0].send_ahrs(ahrs); break; case MSG_SIMSTATE: