2014-01-28 04:31:31 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2014-01-28 04:31:31 -04:00
|
|
|
/*
|
|
|
|
* control_sport.pde - init and run calls for sport flight mode
|
|
|
|
*/
|
|
|
|
|
|
|
|
// sport_init - initialise sport controller
|
2015-05-29 23:12:49 -03:00
|
|
|
bool Copter::sport_init(bool ignore_checks)
|
2014-01-28 04:31:31 -04:00
|
|
|
{
|
2015-10-19 21:05:10 -03:00
|
|
|
// initialize vertical speed and acceleration
|
2014-04-29 23:17:59 -03:00
|
|
|
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
|
|
|
pos_control.set_accel_z(g.pilot_accel_z);
|
|
|
|
|
2015-10-27 10:06:50 -03:00
|
|
|
// initialise position and desired velocity
|
|
|
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
|
|
|
pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z());
|
2014-04-29 23:17:59 -03:00
|
|
|
|
2014-01-28 04:31:31 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// sport_run - runs the sport controller
|
|
|
|
// should be called at 100hz or more
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::sport_run()
|
2014-01-28 04:31:31 -04:00
|
|
|
{
|
|
|
|
float target_roll_rate, target_pitch_rate, target_yaw_rate;
|
|
|
|
float target_climb_rate = 0;
|
2015-04-30 04:40:38 -03:00
|
|
|
float takeoff_climb_rate = 0.0f;
|
2014-01-28 04:31:31 -04:00
|
|
|
|
2015-10-19 21:05:10 -03:00
|
|
|
// initialize vertical speed and acceleration
|
|
|
|
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
|
|
|
pos_control.set_accel_z(g.pilot_accel_z);
|
|
|
|
|
2014-01-28 04:31:31 -04:00
|
|
|
// if not armed or throttle at zero, set throttle to zero and exit immediately
|
2016-01-17 23:53:22 -04:00
|
|
|
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) {
|
2016-02-02 08:16:25 -04:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
2015-04-16 01:54:29 -03:00
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
2016-06-09 09:42:15 -03:00
|
|
|
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-motors.get_throttle_hover());
|
2014-01-28 04:31:31 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// apply SIMPLE mode transform
|
|
|
|
update_simple_mode();
|
|
|
|
|
|
|
|
// get pilot's desired roll and pitch rates
|
2014-02-12 08:55:13 -04:00
|
|
|
|
|
|
|
// calculate rate requests
|
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_roll_rate = channel_roll->get_control_in() * g.acro_rp_p;
|
|
|
|
target_pitch_rate = channel_pitch->get_control_in() * g.acro_rp_p;
|
2014-05-07 05:25:46 -03:00
|
|
|
|
2014-02-12 08:55:13 -04:00
|
|
|
int32_t roll_angle = wrap_180_cd(ahrs.roll_sensor);
|
2014-05-07 05:25:46 -03:00
|
|
|
target_roll_rate -= constrain_int32(roll_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_roll;
|
2014-02-12 08:55:13 -04:00
|
|
|
|
|
|
|
// Calculate trainer mode earth frame rate command for pitch
|
|
|
|
int32_t pitch_angle = wrap_180_cd(ahrs.pitch_sensor);
|
2014-05-07 05:25:46 -03:00
|
|
|
target_pitch_rate -= constrain_int32(pitch_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_pitch;
|
2014-02-12 08:55:13 -04:00
|
|
|
|
|
|
|
if (roll_angle > aparm.angle_max){
|
|
|
|
target_roll_rate -= g.acro_rp_p*(roll_angle-aparm.angle_max);
|
|
|
|
}else if (roll_angle < -aparm.angle_max) {
|
|
|
|
target_roll_rate -= g.acro_rp_p*(roll_angle+aparm.angle_max);
|
|
|
|
}
|
|
|
|
|
|
|
|
if (pitch_angle > aparm.angle_max){
|
|
|
|
target_pitch_rate -= g.acro_rp_p*(pitch_angle-aparm.angle_max);
|
|
|
|
}else if (pitch_angle < -aparm.angle_max) {
|
|
|
|
target_pitch_rate -= g.acro_rp_p*(pitch_angle+aparm.angle_max);
|
|
|
|
}
|
2014-01-28 04:31:31 -04: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());
|
2014-01-28 04:31:31 -04:00
|
|
|
|
|
|
|
// get pilot desired climb 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_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
|
2015-04-30 04:40:38 -03:00
|
|
|
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
|
|
|
|
|
|
|
// get takeoff adjusted pilot and takeoff climb rates
|
|
|
|
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
|
2015-04-30 03:06:55 -03:00
|
|
|
|
|
|
|
// check for take-off
|
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
|
|
|
if (ap.land_complete && (takeoff_state.running || (channel_throttle->get_control_in() > get_takeoff_trigger_throttle()))) {
|
2015-04-30 03:06:55 -03:00
|
|
|
if (!takeoff_state.running) {
|
2015-04-30 02:03:59 -03:00
|
|
|
takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
2015-04-30 03:06:55 -03:00
|
|
|
}
|
2014-01-28 04:31:31 -04:00
|
|
|
|
|
|
|
// indicate we are taking off
|
|
|
|
set_land_complete(false);
|
|
|
|
// clear i term when we're taking off
|
|
|
|
set_throttle_takeoff();
|
|
|
|
}
|
|
|
|
|
|
|
|
// reset target lean angles and heading while landed
|
|
|
|
if (ap.land_complete) {
|
2016-01-17 23:53:22 -04:00
|
|
|
if (ap.throttle_zero) {
|
2016-02-02 08:16:25 -04:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
2016-01-17 23:53:22 -04:00
|
|
|
}else{
|
2016-02-02 08:16:25 -04:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
2016-01-17 23:53:22 -04:00
|
|
|
}
|
2014-07-17 06:18:10 -03:00
|
|
|
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
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
|
|
|
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->get_control_in()),false,g.throttle_filt);
|
2016-06-09 09:42:15 -03:00
|
|
|
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-motors.get_throttle_hover());
|
2014-01-28 04:31:31 -04:00
|
|
|
}else{
|
2016-01-17 23:53:22 -04:00
|
|
|
// set motors to full range
|
2016-02-02 08:16:25 -04:00
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
2014-05-07 05:25:46 -03:00
|
|
|
|
2014-01-28 04:31:31 -04:00
|
|
|
// call attitude controller
|
2015-11-28 13:57:14 -04:00
|
|
|
attitude_control.input_euler_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate);
|
2014-01-28 04:31:31 -04:00
|
|
|
|
2016-04-27 09:18:35 -03:00
|
|
|
// adjust climb rate using rangefinder
|
|
|
|
if (rangefinder_alt_ok()) {
|
2016-04-27 08:37:04 -03:00
|
|
|
// if rangefinder is ok, use surface tracking
|
2015-04-13 15:03:38 -03:00
|
|
|
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
2014-01-28 04:31:31 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// call position controller
|
2015-10-27 10:06:50 -03:00
|
|
|
pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
|
2015-04-30 04:40:38 -03:00
|
|
|
pos_control.add_takeoff_climb_rate(takeoff_climb_rate, G_Dt);
|
2014-01-28 04:31:31 -04:00
|
|
|
pos_control.update_z_controller();
|
|
|
|
}
|
|
|
|
}
|