Copter: Switch PrecLand to use updated Pos Controller

This commit is contained in:
Rishabh 2021-09-06 01:37:57 +05:30 committed by Randy Mackay
parent ef20d749bf
commit 309dfa63f3
5 changed files with 43 additions and 12 deletions

View File

@ -357,6 +357,7 @@ private:
uint8_t unused3 : 1; // 25 // was compass_init_location; true when the compass's initial location has been set uint8_t unused3 : 1; // 25 // was compass_init_location; true when the compass's initial location has been set
uint8_t unused2 : 1; // 26 // aux switch rc_override is allowed uint8_t unused2 : 1; // 26 // aux switch rc_override is allowed
uint8_t armed_with_airmode_switch : 1; // 27 // we armed using a arming switch uint8_t armed_with_airmode_switch : 1; // 27 // we armed using a arming switch
uint8_t prec_land_active : 1; // 28 // true if precland is active
}; };
uint32_t value; uint32_t value;
} ap_t; } ap_t;

View File

@ -641,29 +641,47 @@ void Mode::land_run_horizontal_control()
} }
} }
// this variable will be updated if prec land target is in sight and pilot isn't trying to reposition the vehicle
bool doing_precision_landing = false;
#if PRECISION_LANDING == ENABLED #if PRECISION_LANDING == ENABLED
bool doing_precision_landing = !copter.ap.land_repo_active && copter.precland.target_acquired(); doing_precision_landing = !copter.ap.land_repo_active && copter.precland.target_acquired();
// run precision landing // run precision landing
if (doing_precision_landing) { if (doing_precision_landing) {
Vector2f target_pos, target_vel_rel; Vector2f target_pos, target_vel;
if (!copter.precland.get_target_position_cm(target_pos)) { if (!copter.precland.get_target_position_cm(target_pos)) {
target_pos = inertial_nav.get_position_xy_cm(); target_pos = inertial_nav.get_position_xy_cm();
} }
if (!copter.precland.get_target_velocity_relative_cms(target_vel_rel)) { // get the velocity of the target
target_vel_rel = -inertial_nav.get_velocity_xy_cms(); copter.precland.get_target_velocity_cms(inertial_nav.get_velocity_xy_cms(), target_vel);
}
pos_control->set_pos_target_xy_cm(target_pos.x, target_pos.y); Vector2f zero;
pos_control->override_vehicle_velocity_xy(-target_vel_rel); Vector2p landing_pos = target_pos.topostype();
// target vel will remain zero if landing target is stationary
pos_control->input_pos_vel_accel_xy(landing_pos, target_vel, zero);
// run pos controller
pos_control->update_xy_controller();
} }
#endif #endif
// process roll, pitch inputs if (!doing_precision_landing) {
loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch); if (copter.ap.prec_land_active) {
// precland isn't active anymore but was active a while back
// lets run an init again
// set target to stopping point
Vector2f stopping_point;
loiter_nav->get_stopping_point_xy(stopping_point);
loiter_nav->init_target(stopping_point);
}
// process roll, pitch inputs
loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch);
// run loiter controller // run loiter controller
loiter_nav->update(); loiter_nav->update();
}
Vector3f thrust_vector = loiter_nav->get_thrust_vector(); copter.ap.prec_land_active = doing_precision_landing;
Vector3f thrust_vector = pos_control->get_thrust_vector();
if (g2.wp_navalt_min > 0) { if (g2.wp_navalt_min > 0) {
// user has requested an altitude below which navigation // user has requested an altitude below which navigation

View File

@ -335,6 +335,12 @@ void ModeAuto::land_start(const Vector2f& destination)
// disable the fence on landing // disable the fence on landing
copter.fence.auto_disable_fence_for_landing(); copter.fence.auto_disable_fence_for_landing();
#endif #endif
// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false;
// this will be set true if prec land is later active
copter.ap.prec_land_active = false;
} }
// auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location // auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location

View File

@ -28,6 +28,9 @@ bool ModeLand::init(bool ignore_checks)
// reset flag indicating if pilot has applied roll or pitch inputs during landing // reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false; copter.ap.land_repo_active = false;
// this will be set true if prec land is later active
copter.ap.prec_land_active = false;
// initialise yaw // initialise yaw
auto_yaw.set_mode(AUTO_YAW_HOLD); auto_yaw.set_mode(AUTO_YAW_HOLD);

View File

@ -25,6 +25,9 @@ bool ModeRTL::init(bool ignore_checks)
// reset flag indicating if pilot has applied roll or pitch inputs during landing // reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false; copter.ap.land_repo_active = false;
// this will be set true if prec land is later active
copter.ap.prec_land_active = false;
#if PRECISION_LANDING == ENABLED #if PRECISION_LANDING == ENABLED
// initialise precland state machine // initialise precland state machine
copter.precland_statemachine.init(); copter.precland_statemachine.init();