Browse Source

Plane: use GRAVITY_MSS

mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
4cdb3cd390
  1. 1
      ArduPlane/ArduPlane.pde
  2. 2
      ArduPlane/Attitude.pde
  3. 14
      ArduPlane/GCS_Mavlink.pde

1
ArduPlane/ArduPlane.pde

@ -343,7 +343,6 @@ static bool have_position;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// Constants // Constants
const float radius_of_earth = 6378100; // meters const float radius_of_earth = 6378100; // meters
const float gravity = 9.81; // meters/ sec^2
// This is the currently calculated direction to fly. // This is the currently calculated direction to fly.
// deg * 100 : 0 to 360 // deg * 100 : 0 to 360

2
ArduPlane/Attitude.pde

@ -328,7 +328,7 @@ static void calc_nav_roll()
} }
// Bank angle = V*R/g, where V is airspeed, R is turn rate, and g is gravity. // Bank angle = V*R/g, where V is airspeed, R is turn rate, and g is gravity.
nav_roll = ToDeg(atan(speed*turn_rate/9.81)*100); nav_roll = ToDeg(atan(speed*turn_rate/GRAVITY_MSS)*100);
#else #else
// this is the old nav_roll calculation. We will use this for 2.50 // this is the old nav_roll calculation. We will use this for 2.50

14
ArduPlane/GCS_Mavlink.pde

@ -235,7 +235,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
static void NOINLINE send_meminfo(mavlink_channel_t chan) static void NOINLINE send_meminfo(mavlink_channel_t chan)
{ {
#if CONFIG_HAL_BOARD != HAL_BOARD_AVR_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
extern unsigned __brkval; extern unsigned __brkval;
mavlink_msg_meminfo_send(chan, __brkval, memcheck_available_memory()); mavlink_msg_meminfo_send(chan, __brkval, memcheck_available_memory());
#endif #endif
@ -401,9 +401,9 @@ static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
mavlink_msg_raw_imu_send( mavlink_msg_raw_imu_send(
chan, chan,
micros(), micros(),
accel.x * 1000.0 / gravity, accel.x * 1000.0 / GRAVITY_MSS,
accel.y * 1000.0 / gravity, accel.y * 1000.0 / GRAVITY_MSS,
accel.z * 1000.0 / gravity, accel.z * 1000.0 / GRAVITY_MSS,
gyro.x * 1000.0, gyro.x * 1000.0,
gyro.y * 1000.0, gyro.y * 1000.0,
gyro.z * 1000.0, gyro.z * 1000.0,
@ -1814,9 +1814,9 @@ mission_failed:
// m/s/s // m/s/s
Vector3f accels; Vector3f accels;
accels.x = packet.xacc * (gravity/1000.0); accels.x = packet.xacc * (GRAVITY_MSS/1000.0);
accels.y = packet.yacc * (gravity/1000.0); accels.y = packet.yacc * (GRAVITY_MSS/1000.0);
accels.z = packet.zacc * (gravity/1000.0); accels.z = packet.zacc * (GRAVITY_MSS/1000.0);
ins.set_gyro(gyros); ins.set_gyro(gyros);
ins.set_accel(accels); ins.set_accel(accels);

Loading…
Cancel
Save