2011-12-21 08:25:51 -04:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2015-05-13 03:09:36 -03:00
|
|
|
|
|
|
|
#include "Plane.h"
|
|
|
|
|
2011-12-21 08:25:51 -04:00
|
|
|
/*
|
2012-08-16 21:50:15 -03:00
|
|
|
* failsafe support
|
|
|
|
* Andrew Tridgell, December 2011
|
2011-12-21 08:25:51 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
2012-08-16 21:50:15 -03:00
|
|
|
* our failsafe strategy is to detect main loop lockup and switch to
|
|
|
|
* passing inputs straight from the RC inputs to RC outputs.
|
2011-12-21 08:25:51 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
2012-08-16 21:50:15 -03:00
|
|
|
* this failsafe_check function is called from the core timer interrupt
|
|
|
|
* at 1kHz.
|
2011-12-21 08:25:51 -04:00
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::failsafe_check(void)
|
2011-12-21 08:25:51 -04:00
|
|
|
{
|
|
|
|
static uint16_t last_mainLoop_count;
|
|
|
|
static uint32_t last_timestamp;
|
|
|
|
static bool in_failsafe;
|
2015-05-13 19:05:32 -03:00
|
|
|
uint32_t tnow = micros();
|
2011-12-21 08:25:51 -04:00
|
|
|
|
2016-04-20 22:50:13 -03:00
|
|
|
if (perf.mainLoop_count != last_mainLoop_count) {
|
2011-12-21 08:25:51 -04:00
|
|
|
// the main loop is running, all is OK
|
2016-04-20 22:50:13 -03:00
|
|
|
last_mainLoop_count = perf.mainLoop_count;
|
2011-12-21 08:25:51 -04:00
|
|
|
last_timestamp = tnow;
|
|
|
|
in_failsafe = false;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (tnow - last_timestamp > 200000) {
|
|
|
|
// we have gone at least 0.2 seconds since the main loop
|
2012-08-16 21:50:15 -03:00
|
|
|
// ran. That means we're in trouble, or perhaps are in
|
2011-12-21 08:25:51 -04:00
|
|
|
// an initialisation routine or log erase. Start passing RC
|
|
|
|
// inputs through to outputs
|
|
|
|
in_failsafe = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (in_failsafe && tnow - last_timestamp > 20000) {
|
|
|
|
last_timestamp = tnow;
|
2014-08-25 06:45:39 -03:00
|
|
|
|
2014-09-23 22:03:35 -03:00
|
|
|
if (in_calibration) {
|
|
|
|
// tell the failsafe system that we are calibrating
|
|
|
|
// sensors, so don't trigger failsafe
|
2016-07-22 04:45:05 -03:00
|
|
|
afs.heartbeat();
|
2014-09-23 22:03:35 -03:00
|
|
|
}
|
|
|
|
|
2015-09-06 20:16:14 -03:00
|
|
|
if (hal.rcin->num_channels() < 5) {
|
2014-08-25 06:45:39 -03:00
|
|
|
// we don't have any RC input to pass through
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// pass RC inputs to outputs every 20ms
|
2012-12-04 18:22:21 -04:00
|
|
|
hal.rcin->clear_overrides();
|
ArduPlane: 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:33:02 -03:00
|
|
|
channel_roll->set_radio_out(channel_roll->read());
|
|
|
|
channel_pitch->set_radio_out(channel_pitch->read());
|
2015-03-16 02:45:49 -03:00
|
|
|
if (hal.util->get_soft_armed()) {
|
ArduPlane: 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:33:02 -03:00
|
|
|
channel_throttle->set_radio_out(channel_throttle->read());
|
2015-03-16 02:45:49 -03:00
|
|
|
}
|
ArduPlane: 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:33:02 -03:00
|
|
|
channel_rudder->set_radio_out(channel_rudder->read());
|
2013-06-28 21:14:57 -03:00
|
|
|
|
2014-11-13 20:27:32 -04:00
|
|
|
int16_t roll = channel_roll->pwm_to_angle_dz(0);
|
|
|
|
int16_t pitch = channel_pitch->pwm_to_angle_dz(0);
|
|
|
|
int16_t rudder = channel_rudder->pwm_to_angle_dz(0);
|
|
|
|
|
2013-06-28 21:14:57 -03:00
|
|
|
// setup secondary output channels that don't have
|
|
|
|
// corresponding input channels
|
ArduPlane: 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:33:02 -03:00
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_aileron, roll);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_elevator, pitch);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_rudder, rudder);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_steering, rudder);
|
2013-06-28 21:14:57 -03:00
|
|
|
|
2013-04-28 07:49:53 -03:00
|
|
|
if (g.vtail_output != MIXING_DISABLED) {
|
ArduPlane: 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:33:02 -03:00
|
|
|
channel_output_mixer(g.vtail_output, channel_pitch, channel_rudder);
|
2013-04-28 07:49:53 -03:00
|
|
|
} else if (g.elevon_output != MIXING_DISABLED) {
|
ArduPlane: 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:33:02 -03:00
|
|
|
channel_output_mixer(g.elevon_output, channel_pitch, channel_roll);
|
2012-11-20 22:19:32 -04:00
|
|
|
}
|
2014-04-20 22:51:39 -03:00
|
|
|
|
|
|
|
// this is to allow the failsafe module to deliberately crash
|
|
|
|
// the plane. Only used in extreme circumstances to meet the
|
|
|
|
// OBC rules
|
2016-07-22 05:14:53 -03:00
|
|
|
if (afs.should_crash_vehicle()) {
|
|
|
|
afs.terminate_vehicle();
|
|
|
|
return;
|
|
|
|
}
|
2014-04-20 22:51:39 -03:00
|
|
|
|
2013-04-05 01:35:26 -03:00
|
|
|
if (!demoing_servos) {
|
2013-06-03 03:12:41 -03:00
|
|
|
channel_roll->output();
|
2014-08-07 00:26:47 -03:00
|
|
|
channel_pitch->output();
|
2011-12-21 08:25:51 -04:00
|
|
|
}
|
2013-06-03 03:12:41 -03:00
|
|
|
channel_throttle->output();
|
2015-04-15 22:16:30 -03:00
|
|
|
if (g.rudder_only == 0) {
|
|
|
|
channel_rudder->output();
|
|
|
|
}
|
2013-04-05 01:35:26 -03:00
|
|
|
|
2013-06-28 21:14:57 -03:00
|
|
|
// setup secondary output channels that do have
|
|
|
|
// corresponding input channels
|
2012-11-26 02:16:25 -04:00
|
|
|
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual, true);
|
|
|
|
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_aileron_with_input, true);
|
2013-02-04 17:57:58 -04:00
|
|
|
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_elevator_with_input, true);
|
ArduPlane: 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:33:02 -03:00
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_flap, 0);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_flap_auto, 0);
|
2014-02-05 23:09:49 -04:00
|
|
|
|
|
|
|
// setup flaperons
|
|
|
|
flaperon_update(0);
|
2011-12-21 08:25:51 -04:00
|
|
|
}
|
|
|
|
}
|