mirror of https://github.com/ArduPilot/ardupilot
Added more output to Mavlink for debugging
This commit is contained in:
parent
17ad58fe32
commit
27d9bc92f3
|
@ -111,11 +111,11 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||||
nav_roll / 1.0e2,
|
nav_roll / 1.0e2,
|
||||||
nav_pitch / 1.0e2,
|
nav_pitch / 1.0e2,
|
||||||
target_bearing / 1.0e2,
|
target_bearing / 1.0e2,
|
||||||
target_bearing / 1.0e2,
|
dcm.yaw_sensor / 1.0e2, // was target_bearing
|
||||||
wp_distance,
|
wp_distance,
|
||||||
altitude_error / 1.0e2,
|
altitude_error / 1.0e2,
|
||||||
0,
|
nav_lon, // was 0
|
||||||
0);
|
nav_lat); // was 0
|
||||||
}
|
}
|
||||||
|
|
||||||
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||||
|
@ -128,7 +128,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||||
g_gps->longitude / 1.0e7,
|
g_gps->longitude / 1.0e7,
|
||||||
g_gps->altitude / 100.0,
|
g_gps->altitude / 100.0,
|
||||||
g_gps->hdop,
|
g_gps->hdop,
|
||||||
0.0,
|
current_loc.alt / 100.0, // was 0
|
||||||
g_gps->ground_speed / 100.0,
|
g_gps->ground_speed / 100.0,
|
||||||
g_gps->ground_course / 100.0);
|
g_gps->ground_course / 100.0);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue