Skip to content

Commit

Permalink
Copter: avoid Guided submode change unless can change Loc to Vec-from…
Browse files Browse the repository at this point in the history
…-origin

ordering problem between changing the submode and setting a valid position
  • Loading branch information
peterbarker committed May 21, 2024
1 parent 6a0c12e commit 6256789
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -456,6 +456,13 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y
return true;
}

// set position target and zero velocity and acceleration
Vector3f pos_target_f;
bool terrain_alt;
if (!wp_nav->get_vector_NEU(dest_loc, pos_target_f, terrain_alt)) {
return false;
}

// if configured to use position controller for position control
// ensure we are in position control mode
if (guided_mode != SubMode::Pos) {
Expand All @@ -465,13 +472,6 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y
// set yaw state
set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);

// set position target and zero velocity and acceleration
Vector3f pos_target_f;
bool terrain_alt;
if (!wp_nav->get_vector_NEU(dest_loc, pos_target_f, terrain_alt)) {
return false;
}

// initialise terrain following if needed
if (terrain_alt) {
// get current alt above terrain
Expand Down

0 comments on commit 6256789

Please sign in to comment.