Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: fixed RC failsafe handling for no RC receiver #12291

Merged
merged 1 commit into from Sep 24, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
6 changes: 5 additions & 1 deletion ArduCopter/Attitude.cpp
Expand Up @@ -4,6 +4,10 @@
// returns desired yaw rate in centi-degrees per second
float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle)
{
// throttle failsafe check
if (failsafe.radio || !ap.rc_receiver_present) {
return 0.0f;
}
float yaw_request;

// calculate yaw rate request
Expand Down Expand Up @@ -75,7 +79,7 @@ void Copter::set_throttle_takeoff()
float Copter::get_pilot_desired_climb_rate(float throttle_control)
{
// throttle failsafe check
if (failsafe.radio) {
if (failsafe.radio || !ap.rc_receiver_present) {
return 0.0f;
}

Expand Down
6 changes: 6 additions & 0 deletions ArduCopter/mode.cpp
Expand Up @@ -351,6 +351,12 @@ void Mode::update_navigation()
// returns desired angle in centi-degrees
void Mode::get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
{
// throttle failsafe check
if (copter.failsafe.radio || !copter.ap.rc_receiver_present) {
roll_out = 0;
pitch_out = 0;
return;
}
// fetch roll and pitch inputs
roll_out = channel_roll->get_control_in();
pitch_out = channel_pitch->get_control_in();
Expand Down
7 changes: 2 additions & 5 deletions ArduCopter/radio.cpp
Expand Up @@ -94,11 +94,8 @@ void Copter::read_radio()
set_throttle_and_failsafe(channel_throttle->get_radio_in());
set_throttle_zero_flag(channel_throttle->get_control_in());

if (!ap.rc_receiver_present) {
// RC receiver must be attached if we've just got input and
// there are no overrides
ap.rc_receiver_present = !RC_Channels::has_active_overrides();
}
// RC receiver must be attached if we've just got input
ap.rc_receiver_present = true;

// pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters)
radio_passthrough_to_motors();
Expand Down