Skip to content

Commit

Permalink
AP_ESC_Telem: for RPM, log NaN instead of 0 when there are no measure…
Browse files Browse the repository at this point in the history
…ments
  • Loading branch information
mbuzdalov authored and Pradeep-Carbonix committed Aug 23, 2024
1 parent d8299a2 commit 647150a
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -590,7 +590,7 @@ void AP_ESC_Telem::update()

float rpm = AP::logger().quiet_nanf();
get_rpm(i, rpm);
float raw_rpm = 0.0f;
float raw_rpm = AP::logger().quiet_nanf();
get_raw_rpm(i, raw_rpm);

// Write ESC status messages
Expand Down

0 comments on commit 647150a

Please sign in to comment.