2015-05-13 00:16:45 -03:00
|
|
|
#include "Rover.h"
|
|
|
|
|
2013-06-03 06:33:59 -03:00
|
|
|
/*
|
|
|
|
allow for runtime change of control channel ordering
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::set_control_channels(void)
|
2013-06-03 06:33:59 -03:00
|
|
|
{
|
2017-07-06 00:06:20 -03:00
|
|
|
// check change on RCMAP
|
2017-01-06 06:31:10 -04:00
|
|
|
channel_steer = RC_Channels::rc_channel(rcmap.roll()-1);
|
|
|
|
channel_throttle = RC_Channels::rc_channel(rcmap.throttle()-1);
|
2017-08-22 04:06:23 -03:00
|
|
|
channel_aux = RC_Channels::rc_channel(g.aux_channel-1);
|
2013-06-03 06:33:59 -03:00
|
|
|
|
2016-12-20 09:33:36 -04:00
|
|
|
// set rc channel ranges
|
|
|
|
channel_steer->set_angle(SERVO_MAX);
|
2015-10-30 02:56:41 -03:00
|
|
|
channel_throttle->set_angle(100);
|
|
|
|
|
2017-07-06 07:01:53 -03:00
|
|
|
// Allow to reconfigure ouput when not armed
|
2017-07-06 00:06:20 -03:00
|
|
|
if (!arming.is_armed()) {
|
2017-07-06 07:01:53 -03:00
|
|
|
g2.motors.setup_servo_output();
|
|
|
|
// For a rover safety is TRIM throttle
|
2017-07-06 00:06:20 -03:00
|
|
|
g2.motors.setup_safety_output();
|
2015-10-30 02:56:41 -03:00
|
|
|
}
|
2014-11-20 03:32:08 -04:00
|
|
|
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
2017-05-16 02:16:15 -03:00
|
|
|
// take a proportion of speed. Default to 1000 to 2000 for systems without
|
|
|
|
// a k_throttle output
|
|
|
|
hal.rcout->set_esc_scaling(1000, 2000);
|
|
|
|
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);
|
2013-06-03 09:22:47 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::init_rc_in()
|
2013-06-03 09:22:47 -03:00
|
|
|
{
|
2016-12-20 09:33:36 -04:00
|
|
|
// set rc dead zones
|
|
|
|
channel_steer->set_default_dead_zone(30);
|
|
|
|
channel_throttle->set_default_dead_zone(30);
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::init_rc_out()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-07-10 06:43:55 -03:00
|
|
|
// set auxiliary ranges
|
|
|
|
update_aux();
|
2015-10-30 02:56:41 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
check for driver input on rudder/steering stick for arming/disarming
|
|
|
|
*/
|
|
|
|
void Rover::rudder_arm_disarm_check()
|
|
|
|
{
|
|
|
|
// In Rover we need to check that its set to the throttle trim and within the DZ
|
|
|
|
// if throttle is not within trim dz, then pilot cannot rudder arm/disarm
|
|
|
|
if (!channel_throttle->in_trim_dz()) {
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2018-01-10 21:54:40 -04:00
|
|
|
// check if arming/disarming allowed from this mode
|
|
|
|
if (!control_mode->allows_arming_from_transmitter()) {
|
2015-10-30 02:56:41 -03:00
|
|
|
rudder_arm_timer = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-12-20 09:33:36 -04:00
|
|
|
if (!arming.is_armed()) {
|
|
|
|
// when not armed, full right rudder starts arming counter
|
|
|
|
if (channel_steer->get_control_in() > 4000) {
|
2017-01-31 06:12:26 -04:00
|
|
|
const uint32_t now = millis();
|
2015-10-30 02:56:41 -03:00
|
|
|
|
2016-12-20 09:33:36 -04:00
|
|
|
if (rudder_arm_timer == 0 ||
|
2017-11-30 21:54:45 -04:00
|
|
|
now - rudder_arm_timer < ARM_DELAY_MS) {
|
2016-12-20 09:33:36 -04:00
|
|
|
if (rudder_arm_timer == 0) {
|
2015-10-30 02:56:41 -03:00
|
|
|
rudder_arm_timer = now;
|
|
|
|
}
|
2016-12-20 09:33:36 -04:00
|
|
|
} else {
|
|
|
|
// time to arm!
|
|
|
|
arm_motors(AP_Arming::RUDDER);
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// not at full right rudder
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
2017-11-22 04:39:16 -04:00
|
|
|
} else if (!motor_active()) {
|
2016-12-20 09:33:36 -04:00
|
|
|
// when armed and motor not active (not moving), full left rudder starts disarming counter
|
|
|
|
if (channel_steer->get_control_in() < -4000) {
|
2017-01-31 06:12:26 -04:00
|
|
|
const uint32_t now = millis();
|
2015-10-30 02:56:41 -03:00
|
|
|
|
2016-12-20 09:33:36 -04:00
|
|
|
if (rudder_arm_timer == 0 ||
|
2017-11-30 21:54:45 -04:00
|
|
|
now - rudder_arm_timer < ARM_DELAY_MS) {
|
2016-12-20 09:33:36 -04:00
|
|
|
if (rudder_arm_timer == 0) {
|
2015-10-30 02:56:41 -03:00
|
|
|
rudder_arm_timer = now;
|
|
|
|
}
|
2016-12-20 09:33:36 -04:00
|
|
|
} else {
|
|
|
|
// time to disarm!
|
|
|
|
disarm_motors();
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// not at full left rudder
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::read_radio()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2018-04-24 01:21:18 -03:00
|
|
|
if (!RC_Channels::read_input()) {
|
2017-06-19 12:47:13 -03:00
|
|
|
// check if we lost RC link
|
APMRover2: 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:49:39 -03:00
|
|
|
control_failsafe(channel_throttle->get_radio_in());
|
2013-12-19 18:48:36 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-11-19 23:04:16 -04:00
|
|
|
failsafe.last_valid_rc_ms = AP_HAL::millis();
|
2017-06-19 12:47:13 -03:00
|
|
|
// check that RC value are valid
|
2016-12-20 09:33:36 -04:00
|
|
|
control_failsafe(channel_throttle->get_radio_in());
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-06-19 12:47:13 -03:00
|
|
|
// check if we try to do RC arm/disarm
|
2015-10-30 02:56:41 -03:00
|
|
|
rudder_arm_disarm_check();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::control_failsafe(uint16_t pwm)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2016-12-20 09:33:36 -04:00
|
|
|
if (!g.fs_throttle_enabled) {
|
2013-02-08 06:17:54 -04:00
|
|
|
// no throttle failsafe
|
2016-12-20 09:33:36 -04:00
|
|
|
return;
|
2013-02-08 06:17:54 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2016-12-20 09:33:36 -04:00
|
|
|
// Check for failsafe condition based on loss of GCS control
|
|
|
|
if (rc_override_active) {
|
2013-03-28 20:25:53 -03:00
|
|
|
failsafe_trigger(FAILSAFE_EVENT_RC, (millis() - failsafe.rc_override_timer) > 1500);
|
2016-12-20 09:33:36 -04:00
|
|
|
} else if (g.fs_throttle_enabled) {
|
2017-03-30 11:07:24 -03:00
|
|
|
bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value);
|
2015-11-19 23:04:16 -04:00
|
|
|
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 2000) {
|
2013-12-19 18:48:36 -04:00
|
|
|
failed = true;
|
|
|
|
}
|
|
|
|
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
2016-12-20 09:33:36 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::trim_control_surfaces()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2016-12-20 09:33:36 -04:00
|
|
|
read_radio();
|
|
|
|
// Store control surface trim values
|
|
|
|
// ---------------------------------
|
2017-12-15 02:04:28 -04:00
|
|
|
if ((channel_steer->get_radio_in() > 1400) && (channel_steer->get_radio_in() < 1600)) {
|
2016-12-20 09:33:36 -04:00
|
|
|
channel_steer->set_radio_trim(channel_steer->get_radio_in());
|
2013-02-07 18:21:22 -04:00
|
|
|
// save to eeprom
|
2013-06-03 06:33:59 -03:00
|
|
|
channel_steer->save_eeprom();
|
2012-11-27 17:58:11 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::trim_radio()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-08-22 03:55:39 -03:00
|
|
|
for (uint8_t y = 0; y < 30; y++) {
|
2016-12-20 09:33:36 -04:00
|
|
|
read_radio();
|
|
|
|
}
|
2012-11-27 17:58:11 -04:00
|
|
|
trim_control_surfaces();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|