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
|
2018-05-07 23:35:08 -03:00
|
|
|
channel_steer = rc().channel(rcmap.roll()-1);
|
|
|
|
channel_throttle = rc().channel(rcmap.throttle()-1);
|
|
|
|
channel_lateral = rc().channel(rcmap.yaw()-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);
|
2018-05-10 04:10:34 -03:00
|
|
|
channel_lateral->set_angle(100);
|
2015-10-30 02:56:41 -03:00
|
|
|
|
2019-03-25 20:48:59 -03:00
|
|
|
// Allow to reconfigure output 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);
|
2018-05-10 04:10:34 -03:00
|
|
|
channel_lateral->set_default_dead_zone(30);
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
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()
|
|
|
|
{
|
2018-09-08 00:36:06 -03:00
|
|
|
// check if arming/disarm using rudder is allowed
|
2019-03-07 00:02:01 -04:00
|
|
|
const AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
|
|
|
|
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
|
2018-09-08 00:36:06 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-10-30 02:56:41 -03:00
|
|
|
// 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!
|
2019-03-07 00:02:01 -04:00
|
|
|
arm_motors(AP_Arming::Method::RUDDER);
|
2016-12-20 09:33:36 -04:00
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// not at full right rudder
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
2019-03-07 00:02:01 -04:00
|
|
|
} else if ((arming_rudder == AP_Arming::RudderArming::ARMDISARM) && !g2.motors.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-05-07 23:35:08 -03:00
|
|
|
if (!rc().read_input()) {
|
2017-06-19 12:47:13 -03:00
|
|
|
// check if we lost RC link
|
2018-10-31 02:26:19 -03:00
|
|
|
radio_failsafe_check(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
|
2018-10-31 02:26:19 -03:00
|
|
|
radio_failsafe_check(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
|
|
|
}
|
|
|
|
|
2018-10-31 02:26:19 -03:00
|
|
|
void Rover::radio_failsafe_check(uint16_t pwm)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2016-12-20 09:33:36 -04:00
|
|
|
if (!g.fs_throttle_enabled) {
|
2018-10-31 02:26:19 -03:00
|
|
|
// radio failsafe disabled
|
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
|
|
|
|
2018-08-01 07:39:27 -03:00
|
|
|
bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value);
|
2018-11-01 21:16:34 -03:00
|
|
|
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 200) {
|
2018-08-01 07:39:27 -03:00
|
|
|
failed = true;
|
2016-12-20 09:33:36 -04:00
|
|
|
}
|
2018-08-01 07:39:27 -03:00
|
|
|
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2018-05-25 17:26:55 -03:00
|
|
|
bool Rover::trim_radio()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2018-08-01 07:39:27 -03:00
|
|
|
if (!rc().has_valid_input()) {
|
2018-05-25 17:26:55 -03:00
|
|
|
// can't trim without valid input
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-12-20 09:33:36 -04:00
|
|
|
// 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)) {
|
2018-05-25 17:26:55 -03:00
|
|
|
channel_steer->set_and_save_radio_trim(channel_steer->get_radio_in());
|
|
|
|
} else {
|
|
|
|
return false;
|
2012-11-27 17:58:11 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2018-05-25 17:26:55 -03:00
|
|
|
return true;
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|