AC_Circle: improve target heading

This commit is contained in:
Randy Mackay 2019-04-25 11:35:19 +09:00
parent 0c24810a48
commit b668c6f855
1 changed files with 2 additions and 2 deletions

View File

@ -142,8 +142,8 @@ void AC_Circle::update()
// update position controller target // update position controller target
_pos_control.set_xy_target(target.x, target.y); _pos_control.set_xy_target(target.x, target.y);
// heading is 180 deg from vehicles target position around circle // heading is from vehicle to center of circle
_yaw = wrap_PI(_angle-M_PI) * DEGX100; _yaw = get_bearing_cd(_inav.get_position(), _center);
} else { } else {
// set target position to center // set target position to center
Vector3f target; Vector3f target;