2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2014-01-30 04:40:43 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
/*
|
2016-07-25 15:45:29 -03:00
|
|
|
* Init and run calls for stabilize flight mode for trad heli
|
2014-01-30 04:40:43 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
// stabilize_init - initialise stabilize controller
|
2015-05-29 23:12:49 -03:00
|
|
|
bool Copter::heli_stabilize_init(bool ignore_checks)
|
2014-01-30 04:40:43 -04:00
|
|
|
{
|
|
|
|
// set target altitude to zero for reporting
|
|
|
|
// To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
|
2017-01-09 03:31:26 -04:00
|
|
|
pos_control->set_alt_target(0);
|
2015-10-12 22:05:49 -03:00
|
|
|
|
|
|
|
// set stab collective true to use stabilize scaled collective pitch range
|
|
|
|
input_manager.set_use_stab_col(true);
|
|
|
|
|
2014-01-30 04:40:43 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// stabilize_run - runs the main stabilize controller
|
|
|
|
// should be called at 100hz or more
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::heli_stabilize_run()
|
2014-01-30 04:40:43 -04:00
|
|
|
{
|
2014-12-03 21:25:42 -04:00
|
|
|
float target_roll, target_pitch;
|
2014-01-30 04:40:43 -04:00
|
|
|
float target_yaw_rate;
|
2016-01-04 00:49:05 -04:00
|
|
|
float pilot_throttle_scaled;
|
2014-05-11 13:21:27 -03:00
|
|
|
|
|
|
|
// Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
|
|
|
|
// we may be in autorotation flight. These should be reset only when transitioning from disarmed
|
|
|
|
// to armed, because the pilot will have placed the helicopter down on the landing pad. This is so
|
|
|
|
// that the servos move in a realistic fashion while disarmed for operational checks.
|
|
|
|
// Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
|
|
|
|
2017-01-09 03:31:26 -04:00
|
|
|
if(!motors->armed()) {
|
2014-07-09 16:52:01 -03:00
|
|
|
heli_flags.init_targets_on_arming=true;
|
2017-01-09 03:31:26 -04:00
|
|
|
attitude_control->set_yaw_target_to_current_heading();
|
2014-05-11 13:21:27 -03:00
|
|
|
}
|
|
|
|
|
2017-01-09 03:31:26 -04:00
|
|
|
if(motors->armed() && heli_flags.init_targets_on_arming) {
|
|
|
|
attitude_control->set_yaw_target_to_current_heading();
|
|
|
|
if (motors->rotor_speed_above_critical()) {
|
2015-07-08 16:10:50 -03:00
|
|
|
heli_flags.init_targets_on_arming=false;
|
|
|
|
}
|
2014-05-11 13:21:27 -03:00
|
|
|
}
|
2015-05-23 19:57:17 -03:00
|
|
|
|
2016-08-05 01:36:39 -03:00
|
|
|
// clear landing flag above zero throttle
|
2017-01-09 03:31:26 -04:00
|
|
|
if (motors->armed() && motors->get_interlock() && motors->rotor_runup_complete() && !ap.throttle_zero) {
|
2016-08-05 01:36:39 -03:00
|
|
|
set_land_complete(false);
|
|
|
|
}
|
|
|
|
|
2014-01-30 04:40:43 -04:00
|
|
|
// apply SIMPLE mode transform to pilot inputs
|
|
|
|
update_simple_mode();
|
|
|
|
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
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
|
|
|
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
|
2014-01-30 04:40:43 -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-30 04:40:43 -04:00
|
|
|
|
|
|
|
// get pilot's desired throttle
|
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
|
|
|
pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
|
2014-01-30 04:40:43 -04:00
|
|
|
|
|
|
|
// call attitude controller
|
2017-01-09 03:31:26 -04:00
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
2014-01-30 04:40:43 -04:00
|
|
|
|
|
|
|
// output pilot's throttle - note that TradHeli does not used angle-boost
|
2017-01-09 03:31:26 -04:00
|
|
|
attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
|
2014-01-30 04:40:43 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
#endif //HELI_FRAME
|