2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2018-03-14 17:18:23 -03:00
|
|
|
#if MODE_DRIFT_ENABLED == ENABLED
|
|
|
|
|
2014-01-28 04:31:20 -04:00
|
|
|
/*
|
2016-07-25 15:45:29 -03:00
|
|
|
* Init and run calls for drift flight mode
|
2014-01-28 04:31:20 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
#ifndef DRIFT_SPEEDGAIN
|
2014-11-18 20:18:57 -04:00
|
|
|
# define DRIFT_SPEEDGAIN 8.0f
|
|
|
|
#endif
|
|
|
|
#ifndef DRIFT_SPEEDLIMIT
|
|
|
|
# define DRIFT_SPEEDLIMIT 560.0f
|
2014-03-30 11:00:23 -03:00
|
|
|
#endif
|
|
|
|
|
2014-03-31 03:21:20 -03:00
|
|
|
#ifndef DRIFT_THR_ASSIST_GAIN
|
2016-05-12 19:47:18 -03:00
|
|
|
# define DRIFT_THR_ASSIST_GAIN 0.0018f // gain controlling amount of throttle assistance
|
2014-03-31 01:05:43 -03:00
|
|
|
#endif
|
|
|
|
|
2014-03-31 03:21:20 -03:00
|
|
|
#ifndef DRIFT_THR_ASSIST_MAX
|
2016-01-18 01:37:05 -04:00
|
|
|
# define DRIFT_THR_ASSIST_MAX 0.3f // maximum assistance throttle assist will provide
|
2014-03-31 03:21:20 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef DRIFT_THR_MIN
|
2016-01-18 01:37:05 -04:00
|
|
|
# define DRIFT_THR_MIN 0.213f // throttle assist will be active when pilot's throttle is above this value
|
2014-03-31 03:21:20 -03:00
|
|
|
#endif
|
|
|
|
#ifndef DRIFT_THR_MAX
|
2016-01-18 01:37:05 -04:00
|
|
|
# define DRIFT_THR_MAX 0.787f // throttle assist will be active when pilot's throttle is below this value
|
2014-01-28 04:31:20 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// drift_init - initialise drift controller
|
2019-05-09 23:18:49 -03:00
|
|
|
bool ModeDrift::init(bool ignore_checks)
|
2014-01-28 04:31:20 -04:00
|
|
|
{
|
2019-02-27 23:56:36 -04:00
|
|
|
return true;
|
2014-01-28 04:31:20 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// drift_run - runs the drift controller
|
|
|
|
// should be called at 100hz or more
|
2019-05-09 23:18:49 -03:00
|
|
|
void ModeDrift::run()
|
2014-01-28 04:31:20 -04:00
|
|
|
{
|
2018-01-24 04:09:38 -04:00
|
|
|
static float braker = 0.0f;
|
2015-04-24 02:19:45 -03:00
|
|
|
static float roll_input = 0.0f;
|
2016-08-05 01:36:39 -03:00
|
|
|
|
2014-01-28 04:31:20 -04:00
|
|
|
// convert pilot input to lean angles
|
2019-02-28 05:03:23 -04:00
|
|
|
float target_roll, target_pitch;
|
2018-03-18 08:06:54 -03:00
|
|
|
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
|
2014-01-28 04:31:20 -04:00
|
|
|
|
|
|
|
// Grab inertial velocity
|
2014-04-05 11:19:31 -03:00
|
|
|
const Vector3f& vel = inertial_nav.get_velocity();
|
2014-01-28 04:31:20 -04:00
|
|
|
|
|
|
|
// rotate roll, pitch input from north facing to vehicle's perspective
|
2014-02-08 23:35:22 -04:00
|
|
|
float roll_vel = vel.y * ahrs.cos_yaw() - vel.x * ahrs.sin_yaw(); // body roll vel
|
|
|
|
float pitch_vel = vel.y * ahrs.sin_yaw() + vel.x * ahrs.cos_yaw(); // body pitch vel
|
2014-01-28 04:31:20 -04:00
|
|
|
|
2018-12-28 06:32:57 -04:00
|
|
|
// gain scheduling for yaw
|
2015-11-27 13:11:58 -04:00
|
|
|
float pitch_vel2 = MIN(fabsf(pitch_vel), 2000);
|
2019-02-28 05:03:23 -04:00
|
|
|
float target_yaw_rate = ((float)target_roll/1.0f) * (1.0f - (pitch_vel2 / 5000.0f)) * g.acro_yaw_p;
|
2014-01-28 04:31:20 -04:00
|
|
|
|
2014-11-18 20:18:57 -04:00
|
|
|
roll_vel = constrain_float(roll_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
|
|
|
|
pitch_vel = constrain_float(pitch_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
|
2018-12-28 06:32:57 -04:00
|
|
|
|
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
|
|
|
roll_input = roll_input * .96f + (float)channel_yaw->get_control_in() * .04f;
|
2014-01-28 04:31:20 -04:00
|
|
|
|
2018-12-28 06:32:57 -04:00
|
|
|
// convert user input into desired roll velocity
|
2014-11-18 20:18:57 -04:00
|
|
|
float roll_vel_error = roll_vel - (roll_input / DRIFT_SPEEDGAIN);
|
2014-01-28 04:31:20 -04:00
|
|
|
|
2018-12-28 06:32:57 -04:00
|
|
|
// roll velocity is feed into roll acceleration to minimize slip
|
2014-11-18 20:18:57 -04:00
|
|
|
target_roll = roll_vel_error * -DRIFT_SPEEDGAIN;
|
2016-07-28 18:21:18 -03:00
|
|
|
target_roll = constrain_float(target_roll, -4500.0f, 4500.0f);
|
2014-01-28 04:31:20 -04:00
|
|
|
|
|
|
|
// If we let go of sticks, bring us to a stop
|
2018-12-28 06:32:57 -04:00
|
|
|
if (is_zero(target_pitch)) {
|
2018-01-12 03:41:53 -04:00
|
|
|
// .14/ (.03 * 100) = 4.6 seconds till full braking
|
2018-01-24 04:09:38 -04:00
|
|
|
braker += .03f;
|
|
|
|
braker = MIN(braker, DRIFT_SPEEDGAIN);
|
|
|
|
target_pitch = pitch_vel * braker;
|
2018-12-28 06:32:57 -04:00
|
|
|
} else {
|
2018-01-24 04:09:38 -04:00
|
|
|
braker = 0.0f;
|
2014-01-28 04:31:20 -04:00
|
|
|
}
|
|
|
|
|
2019-02-28 05:03:23 -04:00
|
|
|
if (!motors->armed()) {
|
|
|
|
// Motors should be Stopped
|
2019-04-09 09:16:58 -03:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
2019-05-09 23:18:49 -03:00
|
|
|
} else if (copter.ap.throttle_zero) {
|
2019-02-28 05:03:23 -04:00
|
|
|
// Attempting to Land
|
2019-04-09 09:16:58 -03:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
2019-02-28 05:03:23 -04:00
|
|
|
} else {
|
2019-04-09 09:16:58 -03:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
2019-02-28 05:03:23 -04:00
|
|
|
}
|
|
|
|
|
2019-04-09 09:16:58 -03:00
|
|
|
switch (motors->get_spool_state()) {
|
|
|
|
case AP_Motors::SpoolState::SHUT_DOWN:
|
2019-02-28 05:03:23 -04:00
|
|
|
// Motors Stopped
|
|
|
|
attitude_control->set_yaw_target_to_current_heading();
|
|
|
|
attitude_control->reset_rate_controller_I_terms();
|
2019-04-09 09:16:58 -03:00
|
|
|
break;
|
2019-11-03 22:54:47 -04:00
|
|
|
|
2019-04-09 09:16:58 -03:00
|
|
|
case AP_Motors::SpoolState::GROUND_IDLE:
|
2019-02-28 05:03:23 -04:00
|
|
|
// Landed
|
|
|
|
attitude_control->set_yaw_target_to_current_heading();
|
|
|
|
attitude_control->reset_rate_controller_I_terms();
|
2019-04-09 09:16:58 -03:00
|
|
|
break;
|
2019-11-03 22:54:47 -04:00
|
|
|
|
2019-04-09 09:16:58 -03:00
|
|
|
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
|
2019-02-28 05:03:23 -04:00
|
|
|
// clear landing flag above zero throttle
|
|
|
|
if (!motors->limit.throttle_lower) {
|
|
|
|
set_land_complete(false);
|
|
|
|
}
|
2019-04-09 09:16:58 -03:00
|
|
|
break;
|
2019-11-03 22:54:47 -04:00
|
|
|
|
2019-04-09 09:16:58 -03:00
|
|
|
case AP_Motors::SpoolState::SPOOLING_UP:
|
|
|
|
case AP_Motors::SpoolState::SPOOLING_DOWN:
|
|
|
|
// do nothing
|
|
|
|
break;
|
2019-02-28 05:03:23 -04:00
|
|
|
}
|
2016-01-18 01:37:05 -04:00
|
|
|
|
2014-08-29 01:41:08 -03: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-08-29 01:41:08 -03:00
|
|
|
|
|
|
|
// output pilot's throttle with angle boost
|
2019-03-06 02:36:32 -04:00
|
|
|
const float assisted_throttle = get_throttle_assist(vel.z, get_pilot_desired_throttle());
|
|
|
|
attitude_control->set_throttle_out(assisted_throttle, true, g.throttle_filt);
|
2014-08-29 01:41:08 -03:00
|
|
|
}
|
|
|
|
|
2016-01-18 01:37:05 -04:00
|
|
|
// get_throttle_assist - return throttle output (range 0 ~ 1) based on pilot input and z-axis velocity
|
2019-05-09 23:18:49 -03:00
|
|
|
float ModeDrift::get_throttle_assist(float velz, float pilot_throttle_scaled)
|
2014-08-29 01:41:08 -03:00
|
|
|
{
|
2014-03-31 01:05:43 -03:00
|
|
|
// throttle assist - adjusts throttle to slow the vehicle's vertical velocity
|
|
|
|
// Only active when pilot's throttle is between 213 ~ 787
|
|
|
|
// Assistance is strongest when throttle is at mid, drops linearly to no assistance at 213 and 787
|
2014-03-31 03:21:20 -03:00
|
|
|
float thr_assist = 0.0f;
|
2016-01-18 01:37:05 -04:00
|
|
|
if (pilot_throttle_scaled > DRIFT_THR_MIN && pilot_throttle_scaled < DRIFT_THR_MAX) {
|
2014-03-31 03:21:20 -03:00
|
|
|
// calculate throttle assist gain
|
2016-01-18 01:37:05 -04:00
|
|
|
thr_assist = 1.2f - ((float)fabsf(pilot_throttle_scaled - 0.5f) / 0.24f);
|
2014-08-29 01:41:08 -03:00
|
|
|
thr_assist = constrain_float(thr_assist, 0.0f, 1.0f) * -DRIFT_THR_ASSIST_GAIN * velz;
|
2014-03-31 03:21:20 -03:00
|
|
|
|
|
|
|
// ensure throttle assist never adjusts the throttle by more than 300 pwm
|
|
|
|
thr_assist = constrain_float(thr_assist, -DRIFT_THR_ASSIST_MAX, DRIFT_THR_ASSIST_MAX);
|
|
|
|
}
|
2014-08-29 01:41:08 -03:00
|
|
|
|
2016-01-18 01:37:05 -04:00
|
|
|
return constrain_float(pilot_throttle_scaled + thr_assist, 0.0f, 1.0f);
|
2014-01-28 04:31:20 -04:00
|
|
|
}
|
2018-03-14 17:18:23 -03:00
|
|
|
#endif
|