Skip to content

Commit

Permalink
Plane: try left/right throttle to init ESC scaling
Browse files Browse the repository at this point in the history
Without this, twin motor planes with DroneCAN ESCs need to set a
dummy throttle channel for scale_esc_to_unity to work.
  • Loading branch information
robertlong13 committed Jul 22, 2024
1 parent cb5e49a commit 13271e7
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions ArduPlane/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@ void Plane::set_control_channels(void)
// setup correct scaling for ESCs like the UAVCAN ESCs which
// take a proportion of speed. For quadplanes we use AP_Motors
// scaling
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttleLeft);
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttleRight);
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);
}
}
Expand Down

0 comments on commit 13271e7

Please sign in to comment.