Skip to content

Commit

Permalink
Copter: Change division to multiplication
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura authored and peterbarker committed Jan 2, 2025
1 parent 38c6ae3 commit 20dce34
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduCopter/RC_Channel_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -710,8 +710,8 @@ void RC_Channel_Copter::do_aux_function_change_force_flying(const AuxSwitchPos c
void Copter::save_trim()
{
// save roll and pitch trim
float roll_trim = ToRad((float)channel_roll->get_control_in()/100.0f);
float pitch_trim = ToRad((float)channel_pitch->get_control_in()/100.0f);
float roll_trim = ToRad((float)channel_roll->get_control_in()*0.01f);
float pitch_trim = ToRad((float)channel_pitch->get_control_in()*0.01f);
ahrs.add_trim(roll_trim, pitch_trim);
LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM);
gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
Expand Down

0 comments on commit 20dce34

Please sign in to comment.