|
|
|
@ -1,19 +1,5 @@
@@ -1,19 +1,5 @@
|
|
|
|
|
#include "Sub.h" |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Function that will read the radio data, limit servos and trigger a failsafe
|
|
|
|
|
// ----------------------------------------------------------------------------
|
|
|
|
|
|
|
|
|
|
void Sub::default_dead_zones() |
|
|
|
|
{ |
|
|
|
|
channel_roll->set_default_dead_zone(30); |
|
|
|
|
channel_pitch->set_default_dead_zone(30); |
|
|
|
|
channel_throttle->set_default_dead_zone(30); |
|
|
|
|
channel_yaw->set_default_dead_zone(40); |
|
|
|
|
channel_forward->set_default_dead_zone(30); |
|
|
|
|
channel_lateral->set_default_dead_zone(30); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Sub::init_rc_in() |
|
|
|
|
{ |
|
|
|
|
channel_pitch = RC_Channels::rc_channel(0); |
|
|
|
@ -31,18 +17,13 @@ void Sub::init_rc_in()
@@ -31,18 +17,13 @@ void Sub::init_rc_in()
|
|
|
|
|
channel_forward->set_angle(ROLL_PITCH_INPUT_MAX); |
|
|
|
|
channel_lateral->set_angle(ROLL_PITCH_INPUT_MAX); |
|
|
|
|
|
|
|
|
|
// force throttle trim to 1100
|
|
|
|
|
channel_throttle->set_radio_trim(1100); |
|
|
|
|
channel_throttle->save_eeprom(); |
|
|
|
|
|
|
|
|
|
//set auxiliary servo ranges
|
|
|
|
|
// g.rc_5.set_range(0,1000);
|
|
|
|
|
// g.rc_6.set_range(0,1000);
|
|
|
|
|
// g.rc_7.set_range(0,1000);
|
|
|
|
|
// g.rc_8.set_range(0,1000);
|
|
|
|
|
|
|
|
|
|
// set default dead zones
|
|
|
|
|
default_dead_zones(); |
|
|
|
|
channel_roll->set_default_dead_zone(30); |
|
|
|
|
channel_pitch->set_default_dead_zone(30); |
|
|
|
|
channel_throttle->set_default_dead_zone(30); |
|
|
|
|
channel_yaw->set_default_dead_zone(40); |
|
|
|
|
channel_forward->set_default_dead_zone(30); |
|
|
|
|
channel_lateral->set_default_dead_zone(30); |
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL |
|
|
|
|
// initialize rc input to 1500 on control channels (rather than 0)
|
|
|
|
@ -68,11 +49,3 @@ void Sub::init_rc_out()
@@ -68,11 +49,3 @@ void Sub::init_rc_out()
|
|
|
|
|
// refresh auxiliary channel to function map
|
|
|
|
|
SRV_Channels::update_aux_servo_function(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// enable_motor_output() - enable and output lowest possible value to motors
|
|
|
|
|
void Sub::enable_motor_output() |
|
|
|
|
{ |
|
|
|
|
// enable motors
|
|
|
|
|
motors.enable(); |
|
|
|
|
motors.output_min(); |
|
|
|
|
} |
|
|
|
|