mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
ArduCopter, APM_RC: failsafe if PPM encoder fails to update for 2 seconds
This commit is contained in:
parent
d3c661dd8e
commit
414f9b9759
@ -124,6 +124,8 @@ void output_min()
|
|||||||
motors.enable();
|
motors.enable();
|
||||||
motors.output_min();
|
motors.output_min();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#define RADIO_FS_TIMEOUT_MS 2000 // 2 seconds
|
||||||
static void read_radio()
|
static void read_radio()
|
||||||
{
|
{
|
||||||
if (APM_RC.GetState() == 1) {
|
if (APM_RC.GetState() == 1) {
|
||||||
@ -143,6 +145,11 @@ static void read_radio()
|
|||||||
// limit our input to 800 so we can still pitch and roll
|
// limit our input to 800 so we can still pitch and roll
|
||||||
g.rc_3.control_in = min(g.rc_3.control_in, MAXIMUM_THROTTLE);
|
g.rc_3.control_in = min(g.rc_3.control_in, MAXIMUM_THROTTLE);
|
||||||
#endif
|
#endif
|
||||||
|
}else{
|
||||||
|
// turn on throttle failsafe if no update from ppm encoder for 2 seconds
|
||||||
|
if ((millis() - APM_RC.get_last_update() >= RADIO_FS_TIMEOUT_MS) && g.throttle_fs_enabled && motors.armed() && !ap.failsafe) {
|
||||||
|
set_failsafe(true);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
9
libraries/APM_RC/APM_RC.cpp
Normal file
9
libraries/APM_RC/APM_RC.cpp
Normal file
@ -0,0 +1,9 @@
|
|||||||
|
/*
|
||||||
|
* APM_RC_.cpp - Radio Control Library for Ardupilot Mega. Arduino
|
||||||
|
* Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
#include "APM_RC.h"
|
||||||
|
|
||||||
|
uint32_t APM_RC_Class::_last_update;
|
||||||
|
|
@ -49,10 +49,14 @@ public:
|
|||||||
virtual void Force_Out2_Out3(void) = 0;
|
virtual void Force_Out2_Out3(void) = 0;
|
||||||
virtual void Force_Out6_Out7(void) = 0;
|
virtual void Force_Out6_Out7(void) = 0;
|
||||||
|
|
||||||
|
// get the time of the last radio update
|
||||||
|
virtual uint32_t get_last_update() { return _last_update; };
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
uint16_t _map_speed(uint16_t speed_hz) {
|
uint16_t _map_speed(uint16_t speed_hz) {
|
||||||
return 2000000UL / speed_hz;
|
return 2000000UL / speed_hz;
|
||||||
}
|
}
|
||||||
|
static uint32_t _last_update;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -63,6 +63,7 @@ void APM_RC_APM1::_timer4_capt_cb(void)
|
|||||||
|
|
||||||
if (PPM_Counter >= NUM_CHANNELS) {
|
if (PPM_Counter >= NUM_CHANNELS) {
|
||||||
_radio_status = 1;
|
_radio_status = 1;
|
||||||
|
_last_update = millis();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -316,6 +317,7 @@ bool APM_RC_APM1::setHIL(int16_t v[NUM_CHANNELS])
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
_radio_status = 1;
|
_radio_status = 1;
|
||||||
|
_last_update = millis();
|
||||||
if (sum == 0) {
|
if (sum == 0) {
|
||||||
return 0;
|
return 0;
|
||||||
} else {
|
} else {
|
||||||
|
@ -63,6 +63,7 @@ void APM_RC_APM2::_timer5_capt_cb(void)
|
|||||||
// If this is the last pulse in a frame, set _radio_status.
|
// If this is the last pulse in a frame, set _radio_status.
|
||||||
if (frame_idx >= NUM_CHANNELS) {
|
if (frame_idx >= NUM_CHANNELS) {
|
||||||
_radio_status = 1;
|
_radio_status = 1;
|
||||||
|
_last_update = millis();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -308,12 +309,13 @@ bool APM_RC_APM2::setHIL(int16_t v[NUM_CHANNELS])
|
|||||||
sum++;
|
sum++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
_radio_status = 1;
|
||||||
|
_last_update = millis();
|
||||||
if (sum == 0) {
|
if (sum == 0) {
|
||||||
return 0;
|
return 0;
|
||||||
} else {
|
} else {
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
_radio_status = 1;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void APM_RC_APM2::clearOverride(void)
|
void APM_RC_APM2::clearOverride(void)
|
||||||
|
Loading…
Reference in New Issue
Block a user