ardupilot/ArduCopter/mode_land.cpp

172 lines
5.7 KiB
C++
Raw Normal View History

#include "Copter.h"
// land_init - initialise land controller
bool ModeLand::init(bool ignore_checks)
{
// check if we have GPS and decide which LAND we're going to do
control_position = copter.position_ok();
if (control_position) {
// set target to stopping point
2021-06-21 04:22:48 -03:00
Vector2f stopping_point;
loiter_nav->get_stopping_point_xy(stopping_point);
loiter_nav->init_target(stopping_point);
}
2014-02-15 04:37:24 -04:00
2021-05-19 11:07:38 -03:00
// set vertical speed and acceleration limits
2021-05-11 01:42:02 -03:00
pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
2021-05-19 11:07:38 -03:00
// initialise the vertical position controller
if (!pos_control->is_active_z()) {
2021-05-11 01:42:02 -03:00
pos_control->init_z_controller();
}
2018-10-24 22:23:57 -03:00
land_start_time = millis();
land_pause = false;
// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false;
2019-09-10 01:38:32 -03:00
// initialise yaw
auto_yaw.set_mode(AUTO_YAW_HOLD);
#if LANDING_GEAR_ENABLED == ENABLED
// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
#endif
#if AC_FENCE == ENABLED
// disable the fence on landing
copter.fence.auto_disable_fence_for_landing();
#endif
#if PRECISION_LANDING == ENABLED
// initialise precland state machine
copter.precland_statemachine.init();
#endif
return true;
}
// land_run - runs the land controller
// should be called at 100hz or more
void ModeLand::run()
{
if (control_position) {
gps_run();
2018-10-24 22:23:57 -03:00
} else {
nogps_run();
}
}
// land_gps_run - runs the land controller
// horizontal position controlled with loiter controller
// should be called at 100hz or more
void ModeLand::gps_run()
{
// disarm when the landing detector says we've landed
if (copter.ap.land_complete && motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) {
2020-02-21 09:09:57 -04:00
copter.arming.disarm(AP_Arming::Method::LANDED);
}
2018-10-24 22:23:57 -03:00
// Land State Machine Determination
2019-04-08 05:15:57 -03:00
if (is_disarmed_or_landed()) {
make_safe_ground_handling();
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target();
} else {
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
2018-10-24 22:23:57 -03:00
// pause before beginning land descent
2021-05-12 01:40:33 -03:00
if (land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
land_pause = false;
}
// run normal landing or precision landing (if enabled)
land_run_normal_or_precland(land_pause);
}
}
// land_nogps_run - runs the land controller
// pilot controls roll and pitch angles
// should be called at 100hz or more
void ModeLand::nogps_run()
{
float target_roll = 0.0f, target_pitch = 0.0f;
float target_yaw_rate = 0;
// process pilot inputs
if (!copter.failsafe.radio) {
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT);
// exit land if throttle is high
copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE);
}
if (g.land_repositioning) {
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// get pilot desired lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max_cd());
}
// get pilot's desired yaw rate
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) {
auto_yaw.set_mode(AUTO_YAW_HOLD);
}
}
// disarm when the landing detector says we've landed
if (copter.ap.land_complete && motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) {
2020-02-21 09:09:57 -04:00
copter.arming.disarm(AP_Arming::Method::LANDED);
}
// Land State Machine Determination
2019-04-08 05:15:57 -03:00
if (is_disarmed_or_landed()) {
make_safe_ground_handling();
} else {
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
2016-01-13 03:11:01 -04:00
// pause before beginning land descent
2021-05-12 01:40:33 -03:00
if (land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
land_pause = false;
}
land_run_vertical_control(land_pause);
}
// call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
}
// do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch
// called during GPS failsafe to ensure that if we were already in LAND mode that we do not use the GPS
// has no effect if we are not already in LAND mode
void ModeLand::do_not_use_GPS()
{
control_position = false;
}
// set_mode_land_with_pause - sets mode to LAND and triggers 4 second delay before descent starts
// this is always called from a failsafe so we trigger notification to pilot
void Copter::set_mode_land_with_pause(ModeReason reason)
{
set_mode(Mode::Number::LAND, reason);
mode_land.set_land_pause(true);
// alert pilot to mode change
AP_Notify::events.failsafe_mode_change = 1;
}
// landing_with_GPS - returns true if vehicle is landing using GPS
2018-03-31 02:15:45 -03:00
bool Copter::landing_with_GPS()
{
return (flightmode->mode_number() == Mode::Number::LAND &&
mode_land.controlling_position());
}