mirror of https://github.com/ArduPilot/ardupilot
Sub: auto integrates get-closest-point-on-edge dist
This commit is contained in:
parent
73dfeac547
commit
7c35f967d9
|
@ -187,8 +187,8 @@ void ModeAuto::auto_circle_movetoedge_start(const Location &circle_center, float
|
||||||
|
|
||||||
// check our distance from edge of circle
|
// check our distance from edge of circle
|
||||||
Vector3f circle_edge_neu;
|
Vector3f circle_edge_neu;
|
||||||
sub.circle_nav.get_closest_point_on_circle(circle_edge_neu);
|
float dist_to_edge;
|
||||||
float dist_to_edge = (inertial_nav.get_position_neu_cm() - circle_edge_neu).length();
|
sub.circle_nav.get_closest_point_on_circle(circle_edge_neu, dist_to_edge);
|
||||||
|
|
||||||
// if more than 3m then fly to edge
|
// if more than 3m then fly to edge
|
||||||
if (dist_to_edge > 300.0f) {
|
if (dist_to_edge > 300.0f) {
|
||||||
|
|
Loading…
Reference in New Issue