mirror of https://github.com/ArduPilot/ardupilot
added conversions of CM to M
This commit is contained in:
parent
7edd16e5fe
commit
2fa24e0557
|
@ -270,7 +270,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||||
nav_pitch / 1.0e2,
|
nav_pitch / 1.0e2,
|
||||||
target_bearing / 1.0e2,
|
target_bearing / 1.0e2,
|
||||||
dcm.yaw_sensor / 1.0e2, // was target_bearing
|
dcm.yaw_sensor / 1.0e2, // was target_bearing
|
||||||
wp_distance,
|
wp_distance / 1.0e2,
|
||||||
altitude_error / 1.0e2,
|
altitude_error / 1.0e2,
|
||||||
0,
|
0,
|
||||||
crosstrack_error);
|
crosstrack_error);
|
||||||
|
|
|
@ -118,7 +118,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||||
nav_pitch / 1.0e2,
|
nav_pitch / 1.0e2,
|
||||||
nav_bearing / 1.0e2,
|
nav_bearing / 1.0e2,
|
||||||
target_bearing / 1.0e2,
|
target_bearing / 1.0e2,
|
||||||
wp_distance,
|
wp_distance / 1.0e2,
|
||||||
altitude_error / 1.0e2,
|
altitude_error / 1.0e2,
|
||||||
0,
|
0,
|
||||||
crosstrack_error); // was 0
|
crosstrack_error); // was 0
|
||||||
|
|
Loading…
Reference in New Issue