APM:Copter
radio.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 
4 // Function that will read the radio data, limit servos and trigger a failsafe
5 // ----------------------------------------------------------------------------
6 
8 {
11 #if FRAME_CONFIG == HELI_FRAME
15 #else
18 #endif
20 }
21 
23 {
28 
29  // set rc channel ranges
31  channel_pitch->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
32  channel_yaw->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
33  channel_throttle->set_range(1000);
34 
35  //set auxiliary servo ranges
40 
41  // set default dead zones
43 
44  // initialise throttle_zero flag
45  ap.throttle_zero = true;
46 
47  // Allow override by default at start
48  ap.rc_override_enable = true;
49 }
50 
51  // init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration
53 {
54  motors->set_loop_rate(scheduler.get_loop_rate_hz());
56 
57  // enable aux servos to cope with multiple output channels per motor
59 
60  // update rate must be set after motors->init() to allow for motor mapping
61  motors->set_update_rate(g.rc_speed);
62 
63 #if FRAME_CONFIG != HELI_FRAME
65 #else
66  // setup correct scaling for ESCs like the UAVCAN PX4ESC which
67  // take a proportion of speed.
69 #endif
70 
71  // refresh auxiliary channel to function map
73 
74 #if FRAME_CONFIG != HELI_FRAME
75  /*
76  setup a default safety ignore mask, so that servo gimbals can be active while safety is on
77  */
78  uint16_t safety_ignore_mask = (~copter.motors->get_motor_mask()) & 0x3FFF;
79  BoardConfig.set_default_safety_ignore_mask(safety_ignore_mask);
80 #endif
81 
82  // check if we should enter esc calibration mode
84 }
85 
86 
87 // enable_motor_output() - enable and output lowest possible value to motors
89 {
90  // enable motors
91  motors->output_min();
92 }
93 
95 {
96  uint32_t tnow_ms = millis();
97 
99  ap.new_radio_frame = true;
100 
103 
104  // flag we must have an rc receiver attached
105  if (!failsafe.rc_override_active) {
106  ap.rc_receiver_present = true;
107  }
108 
109  // pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters)
111 
112  float dt = (tnow_ms - last_radio_update_ms)*1.0e-3f;
114  last_radio_update_ms = tnow_ms;
115  }else{
116  uint32_t elapsed = tnow_ms - last_radio_update_ms;
117  // turn on throttle failsafe if no update from the RC Radio for 500ms or 2000ms if we are using RC_OVERRIDE
118  if (((!failsafe.rc_override_active && (elapsed >= FS_RADIO_TIMEOUT_MS)) || (failsafe.rc_override_active && (elapsed >= FS_RADIO_RC_OVERRIDE_TIMEOUT_MS))) &&
119  (g.failsafe_throttle && (ap.rc_receiver_present||motors->armed()) && !failsafe.radio)) {
121  set_failsafe_radio(true);
122  }
123  }
124 }
125 
126 #define FS_COUNTER 3 // radio failsafe kicks in after 3 consecutive throttle values below failsafe_throttle_value
127 void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
128 {
129  // if failsafe not enabled pass through throttle and exit
131  channel_throttle->set_pwm(throttle_pwm);
132  return;
133  }
134 
135  //check for low throttle value
136  if (throttle_pwm < (uint16_t)g.failsafe_throttle_value) {
137 
138  // if we are already in failsafe or motors not armed pass through throttle and exit
139  if (failsafe.radio || !(ap.rc_receiver_present || motors->armed())) {
140  channel_throttle->set_pwm(throttle_pwm);
141  return;
142  }
143 
144  // check for 3 low throttle values
145  // Note: we do not pass through the low throttle until 3 low throttle values are received
146  failsafe.radio_counter++;
147  if( failsafe.radio_counter >= FS_COUNTER ) {
148  failsafe.radio_counter = FS_COUNTER; // check to ensure we don't overflow the counter
149  set_failsafe_radio(true);
150  channel_throttle->set_pwm(throttle_pwm); // pass through failsafe throttle
151  }
152  }else{
153  // we have a good throttle so reduce failsafe counter
154  failsafe.radio_counter--;
155  if( failsafe.radio_counter <= 0 ) {
156  failsafe.radio_counter = 0; // check to ensure we don't underflow the counter
157 
158  // disengage failsafe after three (nearly) consecutive valid throttle values
159  if (failsafe.radio) {
160  set_failsafe_radio(false);
161  }
162  }
163  // pass through throttle
164  channel_throttle->set_pwm(throttle_pwm);
165  }
166 }
167 
168 #define THROTTLE_ZERO_DEBOUNCE_TIME_MS 400
169 // set_throttle_zero_flag - set throttle_zero flag from debounced throttle control
170 // throttle_zero is used to determine if the pilot intends to shut down the motors
171 // Basically, this signals when we are not flying. We are either on the ground
172 // or the pilot has shut down the copter in the air and it is free-falling
173 void Copter::set_throttle_zero_flag(int16_t throttle_control)
174 {
175  static uint32_t last_nonzero_throttle_ms = 0;
176  uint32_t tnow_ms = millis();
177 
178  // if not using throttle interlock and non-zero throttle and not E-stopped,
179  // or using motor interlock and it's enabled, then motors are running,
180  // and we are flying. Immediately set as non-zero
181  if ((!ap.using_interlock && (throttle_control > 0) && !ap.motor_emergency_stop) ||
182  (ap.using_interlock && motors->get_interlock()) ||
183  ap.armed_with_switch) {
184  last_nonzero_throttle_ms = tnow_ms;
185  ap.throttle_zero = false;
186  } else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {
187  ap.throttle_zero = true;
188  }
189 }
190 
191 // pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters)
193 {
194  motors->set_radio_passthrough(channel_roll->norm_input(),
198 }
199 
200 /*
201  return the throttle input for mid-stick as a control-in value
202  */
204 {
205 #if TOY_MODE_ENABLED == ENABLED
206  if (g2.toy_mode.enabled()) {
207  return g2.toy_mode.get_throttle_mid();
208  }
209 #endif
211 }
AP_BoardConfig BoardConfig
Definition: Copter.h:381
void set_range(uint16_t high)
LowPassFilterFloat rc_throttle_control_in_filter
Definition: Copter.h:471
void read_radio()
Definition: radio.cpp:94
AP_Int8 frame_class
Definition: Parameters.h:560
int16_t get_control_mid() const
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
int16_t get_radio_in() const
uint16_t get_loop_rate_hz(void)
static RC_Channel * rc_channel(uint8_t chan)
void radio_passthrough_to_motors()
Definition: radio.cpp:192
#define CH_6
void set_pwm(int16_t pwm)
RC_Channel * channel_roll
Definition: Copter.h:221
ToyMode toy_mode
Definition: Parameters.h:586
void init_rc_out()
Definition: radio.cpp:52
#define CH_5
uint32_t last_radio_update_ms
Definition: Copter.h:583
void set_angle(uint16_t angle)
void set_default_safety_ignore_mask(uint16_t mask)
AP_Int16 failsafe_throttle_value
Definition: Parameters.h:422
void set_throttle_zero_flag(int16_t throttle_control)
Definition: radio.cpp:173
bool enabled(void) const
Definition: toy_mode.h:14
#define ERROR_CODE_RADIO_LATE_FRAME
Definition: defines.h:422
uint8_t roll() const
AP_Int16 rc_speed
Definition: Parameters.h:466
RC_Channel * channel_yaw
Definition: Copter.h:224
static void update_aux_servo_function(void)
MOTOR_CLASS * motors
Definition: Copter.h:422
AP_Int8 frame_type
Definition: Parameters.h:443
#define FS_RADIO_RC_OVERRIDE_TIMEOUT_MS
Definition: config.h:157
uint8_t yaw() const
int16_t get_throttle_mid(void)
Definition: toy_mode.h:21
uint8_t pitch() const
int16_t get_throttle_mid(void)
Definition: radio.cpp:203
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
Definition: Log.cpp:328
RC_Channel * channel_throttle
Definition: Copter.h:223
int16_t get_control_in() const
RC_Channel * channel_pitch
Definition: Copter.h:222
#define f(i)
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
#define FS_THR_DISABLED
Definition: defines.h:455
uint32_t millis()
#define FS_RADIO_TIMEOUT_MS
Definition: config.h:162
void init_rc_in()
Definition: radio.cpp:22
void set_failsafe_radio(bool b)
Definition: AP_State.cpp:47
static void enable_aux_servos(void)
float norm_input()
void set_throttle_and_failsafe(uint16_t throttle_pwm)
Definition: radio.cpp:127
#define ERROR_SUBSYSTEM_RADIO
Definition: defines.h:394
AP_Scheduler scheduler
Definition: Copter.h:212
RCMapper rcmap
Definition: Copter.h:375
Parameters g
Definition: Copter.h:208
int16_t get_control_in_zero_dz(void)
static bool read_input(void)
#define ROLL_PITCH_YAW_INPUT_MAX
Definition: config.h:545
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
int16_t get_radio_min() const
int16_t get_radio_max() const
struct Copter::@2 failsafe
void esc_calibration_startup_check()
uint8_t throttle() const
AP_HAL::RCOutput * rcout
ParametersG2 g2
Definition: Copter.h:209
AP_Int8 failsafe_throttle
Definition: Parameters.h:421
#define FS_COUNTER
Definition: radio.cpp:126
#define CH_8
#define CH_7
void set_default_dead_zone(int16_t dzone)
void enable_motor_output()
Definition: radio.cpp:88
#define THROTTLE_ZERO_DEBOUNCE_TIME_MS
Definition: radio.cpp:168
void default_dead_zones()
Definition: radio.cpp:7
float apply(float sample, float dt)