mirror of https://github.com/ArduPilot/ardupilot
Rover: send y accel in m/s/s as nav_pitch
this allows for easier tuning in MissionPlanner
This commit is contained in:
parent
7789f0d133
commit
6c2f623df2
|
@ -239,8 +239,8 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
|||
{
|
||||
mavlink_msg_nav_controller_output_send(
|
||||
chan,
|
||||
lateral_acceleration,
|
||||
0,
|
||||
lateral_acceleration, // use nav_roll to hold demanded Y accel
|
||||
ins.get_accel().y, // use nav_pitch to hold actual Y accel
|
||||
nav_controller->nav_bearing_cd() * 0.01f,
|
||||
nav_controller->target_bearing_cd() * 0.01f,
|
||||
wp_distance,
|
||||
|
|
Loading…
Reference in New Issue