2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2016-03-22 00:24:56 -03:00
|
|
|
// FIXME? why are these static?
|
2014-01-24 02:47:42 -04:00
|
|
|
static bool land_with_gps;
|
|
|
|
|
2014-07-06 06:16:27 -03:00
|
|
|
static uint32_t land_start_time;
|
|
|
|
static bool land_pause;
|
|
|
|
|
2014-01-24 02:47:42 -04:00
|
|
|
// land_init - initialise land controller
|
2017-12-10 23:51:13 -04:00
|
|
|
bool Copter::ModeLand::init(bool ignore_checks)
|
2014-01-24 02:47:42 -04:00
|
|
|
{
|
|
|
|
// check if we have GPS and decide which LAND we're going to do
|
2018-02-07 22:21:09 -04:00
|
|
|
land_with_gps = copter.position_ok();
|
2014-01-24 02:47:42 -04:00
|
|
|
if (land_with_gps) {
|
2014-01-25 00:41:17 -04:00
|
|
|
// set target to stopping point
|
|
|
|
Vector3f stopping_point;
|
2018-03-27 23:13:37 -03:00
|
|
|
loiter_nav->get_stopping_point_xy(stopping_point);
|
|
|
|
loiter_nav->init_target(stopping_point);
|
2014-01-24 02:47:42 -04:00
|
|
|
}
|
2014-02-15 04:37:24 -04:00
|
|
|
|
2014-04-29 23:17:59 -03:00
|
|
|
// initialize vertical speeds and leash lengths
|
2017-01-09 03:31:26 -04:00
|
|
|
pos_control->set_speed_z(wp_nav->get_speed_down(), wp_nav->get_speed_up());
|
|
|
|
pos_control->set_accel_z(wp_nav->get_accel_z());
|
2014-04-30 04:29:32 -03:00
|
|
|
|
2016-07-07 21:41:38 -03:00
|
|
|
// initialise position and desired velocity
|
2017-01-09 03:31:26 -04:00
|
|
|
if (!pos_control->is_active_z()) {
|
|
|
|
pos_control->set_alt_target_to_current_alt();
|
|
|
|
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
|
2016-10-14 09:28:32 -03:00
|
|
|
}
|
2016-07-07 21:41:38 -03:00
|
|
|
|
2014-07-06 06:16:27 -03:00
|
|
|
land_start_time = millis();
|
|
|
|
|
|
|
|
land_pause = false;
|
|
|
|
|
2015-08-28 05:14:40 -03:00
|
|
|
// reset flag indicating if pilot has applied roll or pitch inputs during landing
|
|
|
|
ap.land_repo_active = false;
|
|
|
|
|
2014-01-24 02:47:42 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// land_run - runs the land controller
|
|
|
|
// should be called at 100hz or more
|
2017-12-10 23:51:13 -04:00
|
|
|
void Copter::ModeLand::run()
|
2014-01-24 02:47:42 -04:00
|
|
|
{
|
2014-01-24 03:23:33 -04:00
|
|
|
if (land_with_gps) {
|
2016-03-22 00:24:56 -03:00
|
|
|
gps_run();
|
2014-01-24 03:23:33 -04:00
|
|
|
}else{
|
2016-03-22 00:24:56 -03:00
|
|
|
nogps_run();
|
2014-01-24 03:23:33 -04:00
|
|
|
}
|
|
|
|
}
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2017-11-15 11:19:47 -04:00
|
|
|
// land_gps_run - runs the land controller
|
2014-01-24 03:23:33 -04:00
|
|
|
// horizontal position controlled with loiter controller
|
|
|
|
// should be called at 100hz or more
|
2017-12-10 23:51:13 -04:00
|
|
|
void Copter::ModeLand::gps_run()
|
2014-01-24 03:23:33 -04:00
|
|
|
{
|
2015-04-17 14:49:08 -03:00
|
|
|
// if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
|
2017-01-09 03:31:26 -04:00
|
|
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
|
2016-11-17 01:47:41 -04:00
|
|
|
zero_throttle_and_relax_ac();
|
2018-03-27 23:13:37 -03:00
|
|
|
loiter_nav->init_target();
|
2014-01-24 02:47:42 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// disarm when the landing detector says we've landed
|
|
|
|
if (ap.land_complete) {
|
2018-02-07 22:21:09 -04:00
|
|
|
copter.init_disarm_motors();
|
2014-01-24 03:23:33 -04:00
|
|
|
}
|
2014-01-24 02:47:42 -04:00
|
|
|
return;
|
|
|
|
}
|
2016-07-07 21:41:38 -03:00
|
|
|
|
2016-01-13 03:11:01 -04:00
|
|
|
// set motors to full range
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
2016-07-07 21:41:38 -03:00
|
|
|
|
|
|
|
// pause before beginning land descent
|
|
|
|
if(land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
|
2014-07-06 06:16:27 -03:00
|
|
|
land_pause = false;
|
|
|
|
}
|
2016-07-07 21:41:38 -03:00
|
|
|
|
2018-03-19 14:26:35 -03:00
|
|
|
land_run_horizontal_control();
|
|
|
|
land_run_vertical_control(land_pause);
|
2014-01-24 03:23:33 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// land_nogps_run - runs the land controller
|
|
|
|
// pilot controls roll and pitch angles
|
|
|
|
// should be called at 100hz or more
|
2017-12-10 23:51:13 -04:00
|
|
|
void Copter::ModeLand::nogps_run()
|
2014-01-24 03:23:33 -04:00
|
|
|
{
|
2014-12-03 21:25:42 -04:00
|
|
|
float target_roll = 0.0f, target_pitch = 0.0f;
|
2014-01-24 03:23:33 -04:00
|
|
|
float target_yaw_rate = 0;
|
|
|
|
|
2015-07-01 15:38:32 -03:00
|
|
|
// process pilot inputs
|
2018-02-07 22:21:09 -04:00
|
|
|
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){
|
2016-01-14 01:47:26 -04:00
|
|
|
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
2016-01-06 17:39:36 -04:00
|
|
|
// exit land if throttle is high
|
2018-02-07 22:21:09 -04:00
|
|
|
copter.set_mode(ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE);
|
2016-01-06 17:39:36 -04:00
|
|
|
}
|
|
|
|
|
2015-07-01 15:38:32 -03:00
|
|
|
if (g.land_repositioning) {
|
|
|
|
// apply SIMPLE mode transform to pilot inputs
|
|
|
|
update_simple_mode();
|
|
|
|
|
|
|
|
// get pilot desired lean angles
|
2018-03-18 08:06:54 -03:00
|
|
|
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max());
|
2015-07-01 15:38:32 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// 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());
|
2015-07-01 15:38:32 -03:00
|
|
|
}
|
|
|
|
|
2015-04-17 14:49:08 -03:00
|
|
|
// if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
|
2017-01-09 03:31:26 -04:00
|
|
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
|
2015-07-01 15:38:32 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
|
|
|
// call attitude controller
|
2017-06-26 05:48:04 -03:00
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
2017-01-09 03:31:26 -04:00
|
|
|
attitude_control->set_throttle_out(0,false,g.throttle_filt);
|
2016-01-13 03:11:01 -04:00
|
|
|
#else
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
2016-01-13 03:11:01 -04:00
|
|
|
// multicopters do not stabilize roll/pitch/yaw when disarmed
|
2017-01-09 03:31:26 -04:00
|
|
|
attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
2015-07-01 15:38:32 -03:00
|
|
|
#endif
|
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// disarm when the landing detector says we've landed
|
|
|
|
if (ap.land_complete) {
|
2018-02-07 22:21:09 -04:00
|
|
|
copter.init_disarm_motors();
|
2014-01-24 03:23:33 -04:00
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-01-13 03:11:01 -04:00
|
|
|
// set motors to full range
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
2016-01-13 03:11:01 -04:00
|
|
|
|
2014-01-24 03:23:33 -04:00
|
|
|
// call attitude controller
|
2017-06-26 05:48:04 -03:00
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
2014-01-24 03:23:33 -04:00
|
|
|
|
2016-07-07 21:41:38 -03:00
|
|
|
// pause before beginning land descent
|
|
|
|
if(land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
|
2014-07-06 06:16:27 -03:00
|
|
|
land_pause = false;
|
2016-07-07 21:41:38 -03:00
|
|
|
}
|
|
|
|
|
2018-03-19 14:26:35 -03:00
|
|
|
land_run_vertical_control(land_pause);
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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 Copter::ModeLand::do_not_use_GPS()
|
|
|
|
{
|
|
|
|
land_with_gps = false;
|
2016-07-07 21:41:38 -03:00
|
|
|
}
|
|
|
|
|
2014-07-06 06:16:27 -03:00
|
|
|
// set_mode_land_with_pause - sets mode to LAND and triggers 4 second delay before descent starts
|
2014-12-14 23:48:54 -04:00
|
|
|
// this is always called from a failsafe so we trigger notification to pilot
|
2016-01-25 19:40:41 -04:00
|
|
|
void Copter::set_mode_land_with_pause(mode_reason_t reason)
|
2014-07-06 06:16:27 -03:00
|
|
|
{
|
2016-01-25 19:40:41 -04:00
|
|
|
set_mode(LAND, reason);
|
2014-07-06 06:16:27 -03:00
|
|
|
land_pause = true;
|
2014-12-14 23:48:54 -04:00
|
|
|
|
|
|
|
// alert pilot to mode change
|
|
|
|
AP_Notify::events.failsafe_mode_change = 1;
|
2014-07-06 06:16:27 -03:00
|
|
|
}
|
2014-09-15 21:16:41 -03:00
|
|
|
|
|
|
|
// landing_with_GPS - returns true if vehicle is landing using GPS
|
2018-03-31 02:15:45 -03:00
|
|
|
bool Copter::landing_with_GPS()
|
|
|
|
{
|
2014-09-15 21:16:41 -03:00
|
|
|
return (control_mode == LAND && land_with_gps);
|
|
|
|
}
|