ardupilot/ArduPlane/radio.pde

239 lines
8.4 KiB
Plaintext
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//Function that will read the radio data, limit servos and trigger a failsafe
// ----------------------------------------------------------------------------
2012-12-04 18:22:21 -04:00
static uint8_t failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
/*
allow for runtime change of control channel ordering
*/
static void set_control_channels(void)
{
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
channel_rudder = RC_Channel::rc_channel(rcmap.yaw()-1);
}
/*
initialise RC input channels
*/
static void init_rc_in()
{
2012-08-21 23:19:50 -03:00
// set rc channel ranges
channel_roll->set_angle(SERVO_MAX);
channel_pitch->set_angle(SERVO_MAX);
channel_rudder->set_angle(SERVO_MAX);
channel_throttle->set_range(0, 100);
2012-08-21 23:19:50 -03:00
// set rc dead zones
channel_roll->set_dead_zone(60);
channel_pitch->set_dead_zone(60);
channel_rudder->set_dead_zone(60);
channel_throttle->set_dead_zone(6);
2012-08-21 23:19:50 -03:00
//channel_roll->dead_zone = 60;
//channel_pitch->dead_zone = 60;
//channel_rudder->dead_zone = 60;
//channel_throttle->dead_zone = 6;
2012-08-21 23:19:50 -03:00
//set auxiliary ranges
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11, &g.rc_12);
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
2012-08-21 23:19:50 -03:00
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11);
#else
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
#endif
}
/*
initialise RC output channels
*/
static void init_rc_out()
{
channel_roll->enable_out();
channel_pitch->enable_out();
channel_throttle->enable_out();
channel_rudder->enable_out();
2012-08-21 23:19:50 -03:00
enable_aux_servos();
2012-08-04 13:39:20 -03:00
2012-09-16 02:51:13 -03:00
// Initialization of servo outputs
for (uint8_t i=0; i<8; i++) {
RC_Channel::rc_channel(i)->output_trim();
}
2012-08-04 13:39:20 -03:00
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
servo_write(CH_9, g.rc_9.radio_trim);
servo_write(CH_10, g.rc_10.radio_trim);
servo_write(CH_11, g.rc_11.radio_trim);
2012-08-04 13:39:20 -03:00
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
servo_write(CH_12, g.rc_12.radio_trim);
#endif
}
static void read_radio()
{
elevon.ch1_temp = channel_roll->read();
elevon.ch2_temp = channel_pitch->read();
uint16_t pwm_roll, pwm_pitch;
2012-08-21 23:19:50 -03:00
if (g.mix_mode == 0) {
pwm_roll = elevon.ch1_temp;
pwm_pitch = elevon.ch2_temp;
2012-08-21 23:19:50 -03:00
}else{
pwm_roll = BOOL_TO_SIGN(g.reverse_elevons) * (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2) - BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
pwm_pitch = (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2) + BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
}
if (control_mode == TRAINING) {
// in training mode we don't want to use a deadzone, as we
// want manual pass through when not exceeding attitude limits
channel_roll->set_pwm_no_deadzone(pwm_roll);
channel_pitch->set_pwm_no_deadzone(pwm_pitch);
channel_throttle->set_pwm_no_deadzone(channel_throttle->read());
channel_rudder->set_pwm_no_deadzone(channel_rudder->read());
} else {
channel_roll->set_pwm(pwm_roll);
channel_pitch->set_pwm(pwm_pitch);
channel_throttle->set_pwm(channel_throttle->read());
channel_rudder->set_pwm(channel_rudder->read());
2012-08-21 23:19:50 -03:00
}
2012-12-04 18:22:21 -04:00
g.rc_5.set_pwm(hal.rcin->read(CH_5));
g.rc_6.set_pwm(hal.rcin->read(CH_6));
g.rc_7.set_pwm(hal.rcin->read(CH_7));
g.rc_8.set_pwm(hal.rcin->read(CH_8));
2012-08-21 23:19:50 -03:00
control_failsafe(channel_throttle->radio_in);
2012-08-21 23:19:50 -03:00
channel_throttle->servo_out = channel_throttle->control_in;
2012-08-21 23:19:50 -03:00
if (g.throttle_nudge && channel_throttle->servo_out > 50) {
float nudge = (channel_throttle->servo_out - 50) * 0.02;
if (alt_control_airspeed()) {
airspeed_nudge_cm = (g.flybywire_airspeed_max * 100 - g.airspeed_cruise_cm) * nudge;
2012-08-21 23:19:50 -03:00
} else {
throttle_nudge = (g.throttle_max - g.throttle_cruise) * nudge;
2012-08-21 23:19:50 -03:00
}
} else {
airspeed_nudge_cm = 0;
throttle_nudge = 0;
}
/*
* cliSerial->printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d \n"),
2012-08-21 23:19:50 -03:00
* (int)g.rc_1.control_in,
* (int)g.rc_2.control_in,
* (int)g.rc_3.control_in,
* (int)g.rc_4.control_in);
*/
}
static void control_failsafe(uint16_t pwm)
{
2012-08-21 23:19:50 -03:00
if(g.throttle_fs_enabled == 0)
return;
// Check for failsafe condition based on loss of GCS control
if (rc_override_active) {
if (millis() - last_heartbeat_ms > FAILSAFE_SHORT_TIME) {
2012-08-21 23:19:50 -03:00
ch3_failsafe = true;
} else {
ch3_failsafe = false;
}
//Check for failsafe and debounce funky reads
} else if (g.throttle_fs_enabled) {
if (pwm < (unsigned)g.throttle_fs_value) {
// we detect a failsafe from radio
// throttle has dropped below the mark
failsafeCounter++;
if (failsafeCounter == 9) {
gcs_send_text_fmt(PSTR("MSG FS ON %u"), (unsigned)pwm);
}else if(failsafeCounter == 10) {
ch3_failsafe = true;
}else if (failsafeCounter > 10) {
failsafeCounter = 11;
}
}else if(failsafeCounter > 0) {
// we are no longer in failsafe condition
// but we need to recover quickly
failsafeCounter--;
if (failsafeCounter > 3) {
failsafeCounter = 3;
}
if (failsafeCounter == 1) {
gcs_send_text_fmt(PSTR("MSG FS OFF %u"), (unsigned)pwm);
2013-01-15 23:19:25 -04:00
} else if(failsafeCounter == 0) {
2012-08-21 23:19:50 -03:00
ch3_failsafe = false;
}
}
}
}
static void trim_control_surfaces()
{
2012-08-21 23:19:50 -03:00
read_radio();
int16_t trim_roll_range = (channel_roll->radio_max - channel_roll->radio_min)/5;
int16_t trim_pitch_range = (channel_pitch->radio_max - channel_pitch->radio_min)/5;
if (channel_roll->radio_in < channel_roll->radio_min+trim_roll_range ||
channel_roll->radio_in > channel_roll->radio_max-trim_roll_range ||
channel_pitch->radio_in < channel_pitch->radio_min+trim_pitch_range ||
channel_pitch->radio_in > channel_pitch->radio_max-trim_pitch_range) {
// don't trim for extreme values - if we attempt to trim so
// there is less than 20 percent range left then assume the
// sticks are not properly centered. This also prevents
// problems with starting APM with the TX off
return;
}
2012-08-21 23:19:50 -03:00
// Store control surface trim values
// ---------------------------------
if(g.mix_mode == 0) {
if (channel_roll->radio_in != 0) {
channel_roll->radio_trim = channel_roll->radio_in;
}
if (channel_pitch->radio_in != 0) {
channel_pitch->radio_trim = channel_pitch->radio_in;
}
// the secondary aileron/elevator is trimmed only if it has a
// corresponding transmitter input channel, which k_aileron
// doesn't have
RC_Channel_aux::set_radio_trim(RC_Channel_aux::k_aileron_with_input);
RC_Channel_aux::set_radio_trim(RC_Channel_aux::k_elevator_with_input);
} else{
if (elevon.ch1_temp != 0) {
elevon.trim1 = elevon.ch1_temp;
}
if (elevon.ch2_temp != 0) {
elevon.trim2 = elevon.ch2_temp;
}
2012-08-21 23:19:50 -03:00
//Recompute values here using new values for elevon1_trim and elevon2_trim
//We cannot use radio_in[CH_ROLL] and radio_in[CH_PITCH] values from read_radio() because the elevon trim values have changed
uint16_t center = 1500;
channel_roll->radio_trim = center;
channel_pitch->radio_trim = center;
2012-08-21 23:19:50 -03:00
}
if (channel_rudder->radio_in != 0) {
channel_rudder->radio_trim = channel_rudder->radio_in;
}
2012-08-21 23:19:50 -03:00
// save to eeprom
channel_roll->save_eeprom();
channel_pitch->save_eeprom();
channel_rudder->save_eeprom();
}
static void trim_radio()
{
for (uint8_t y = 0; y < 30; y++) {
2012-08-21 23:19:50 -03:00
read_radio();
}
trim_control_surfaces();
}