Skip to content

Commit

Permalink
AP_Periph: always limit rangefinder update rate to given max rate
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed May 8, 2024
1 parent 13cbffe commit bcf0733
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion Tools/AP_Periph/rangefinder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
// limit to max rate
return;
}
last_rangefinder_update_ms = now;

// update all rangefinder instances
rangefinder.update();
Expand Down Expand Up @@ -114,7 +115,6 @@ void AP_Periph_FW::can_rangefinder_update(void)
&buffer[0],
total_size);

last_rangefinder_update_ms = now;
}
}

Expand Down

0 comments on commit bcf0733

Please sign in to comment.