diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index 166025e154..4b3dcf912e 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -101,6 +101,13 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @User: Advanced AP_GROUPINFO("PORT", 8, AP_BLHeli, control_port, 0), + // @Param: POLES + // @DisplayName: Motor Poles + // @Description: This allows calculation of true RPM from ESC's eRPM. The default is 14. + // @Values: 1-127 + // @User: Advanced + AP_GROUPINFO("POLES", 9, AP_BLHeli, motor_poles, 14), + AP_GROUPEND }; @@ -1327,7 +1334,7 @@ void AP_BLHeli::read_telemetry_packet(void) td.voltage = (buf[1]<<8) | buf[2]; td.current = (buf[3]<<8) | buf[4]; td.consumption = (buf[5]<<8) | buf[6]; - td.rpm = (buf[7]<<8) | buf[8]; + td.rpm = ((buf[7]<<8) | buf[8]) * motor_poles; td.timestamp_ms = AP_HAL::millis(); last_telem[last_telem_esc] = td; diff --git a/libraries/AP_BLHeli/AP_BLHeli.h b/libraries/AP_BLHeli/AP_BLHeli.h index 4f741dbc40..a1b4acb95f 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.h +++ b/libraries/AP_BLHeli/AP_BLHeli.h @@ -77,6 +77,7 @@ private: AP_Int8 debug_level; AP_Int8 output_type; AP_Int8 control_port; + AP_Int8 motor_poles; enum mspState { MSP_IDLE=0, diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 7ebd6d809f..e0ee318eda 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -752,9 +752,7 @@ void AP_OSD_Screen::draw_blh_rpm(uint8_t x, uint8_t y) if (!blheli->get_telem_data(0, td)) { return; } - - int esc_rpm = td.rpm * 14; // hard-wired assumption for now that motor has 14 poles, so multiply eRPM * 14 to get motor RPM. - backend->write(x, y, false, "%5d%c", esc_rpm, SYM_RPM); + backend->write(x, y, false, "%5d%c", td.rpm, SYM_RPM); } }