diff --git a/libraries/AP_MSP/AP_MSP.cpp b/libraries/AP_MSP/AP_MSP.cpp index 33fd747e03..40115a4c0e 100644 --- a/libraries/AP_MSP/AP_MSP.cpp +++ b/libraries/AP_MSP/AP_MSP.cpp @@ -150,7 +150,7 @@ void AP_MSP::init_osd() _osd_item_settings[OSD_NUMERICAL_HEADING] = &osd->screen[0].heading; _osd_item_settings[OSD_NUMERICAL_VARIO] = &osd->screen[0].vspeed; #if HAL_WITH_ESC_TELEM - _osd_item_settings[OSD_ESC_TMP] = &osd->screen[0].blh_temp; + _osd_item_settings[OSD_ESC_TMP] = &osd->screen[0].esc_temp; #endif _osd_item_settings[OSD_RTC_DATETIME] = &osd->screen[0].clk; #endif // OSD_ENABLED diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index 698c4f71d3..adaa36bbe0 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -156,9 +156,9 @@ private: AP_OSD_Setting aspd2{false, 0, 0}; AP_OSD_Setting vspeed{true, 24, 9}; #if HAL_WITH_ESC_TELEM - AP_OSD_Setting blh_temp {false, 24, 13}; - AP_OSD_Setting blh_rpm{false, 22, 12}; - AP_OSD_Setting blh_amps{false, 24, 14}; + AP_OSD_Setting esc_temp {false, 24, 13}; + AP_OSD_Setting esc_rpm{false, 22, 12}; + AP_OSD_Setting esc_amps{false, 24, 14}; #endif AP_OSD_Setting gps_latitude{true, 9, 13}; AP_OSD_Setting gps_longitude{true, 9, 14}; @@ -228,9 +228,9 @@ private: void draw_speed(uint8_t x, uint8_t y, float angle_rad, float magnitude); void draw_distance(uint8_t x, uint8_t y, float distance); #if HAL_WITH_ESC_TELEM - void draw_blh_temp(uint8_t x, uint8_t y); - void draw_blh_rpm(uint8_t x, uint8_t y); - void draw_blh_amps(uint8_t x, uint8_t y); + void draw_esc_temp(uint8_t x, uint8_t y); + void draw_esc_rpm(uint8_t x, uint8_t y); + void draw_esc_amps(uint8_t x, uint8_t y); #endif void draw_gps_latitude(uint8_t x, uint8_t y); void draw_gps_longitude(uint8_t x, uint8_t y); diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 1d47ad9adf..187af883d4 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -346,53 +346,53 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { AP_SUBGROUPINFO(vspeed, "VSPEED", 20, AP_OSD_Screen, AP_OSD_Setting), #if HAL_WITH_ESC_TELEM - // @Param: BLHTEMP_EN - // @DisplayName: BLHTEMP_EN + // @Param: ESCTEMP_EN + // @DisplayName: ESCTEMP_EN // @Description: Displays first esc's temp // @Values: 0:Disabled,1:Enabled - // @Param: BLHTEMP_X - // @DisplayName: BLHTEMP_X + // @Param: ESCTEMP_X + // @DisplayName: ESCTEMP_X // @Description: Horizontal position on screen // @Range: 0 29 - // @Param: BLHTEMP_Y - // @DisplayName: BLHTEMP_Y + // @Param: ESCTEMP_Y + // @DisplayName: ESCTEMP_Y // @Description: Vertical position on screen // @Range: 0 15 - AP_SUBGROUPINFO(blh_temp, "BLHTEMP", 21, AP_OSD_Screen, AP_OSD_Setting), + AP_SUBGROUPINFO(esc_temp, "ESCTEMP", 21, AP_OSD_Screen, AP_OSD_Setting), - // @Param: BLHRPM_EN - // @DisplayName: BLHRPM_EN + // @Param: ESCRPM_EN + // @DisplayName: ESCRPM_EN // @Description: Displays first esc's rpm // @Values: 0:Disabled,1:Enabled - // @Param: BLHRPM_X - // @DisplayName: BLHRPM_X + // @Param: ESCRPM_X + // @DisplayName: ESCRPM_X // @Description: Horizontal position on screen // @Range: 0 29 - // @Param: BLHRPM_Y - // @DisplayName: BLHRPM_Y + // @Param: ESCRPM_Y + // @DisplayName: ESCRPM_Y // @Description: Vertical position on screen // @Range: 0 15 - AP_SUBGROUPINFO(blh_rpm, "BLHRPM", 22, AP_OSD_Screen, AP_OSD_Setting), + AP_SUBGROUPINFO(esc_rpm, "ESCRPM", 22, AP_OSD_Screen, AP_OSD_Setting), - // @Param: BLHAMPS_EN - // @DisplayName: BLHAMPS_EN + // @Param: ESCAMPS_EN + // @DisplayName: ESCAMPS_EN // @Description: Displays first esc's current // @Values: 0:Disabled,1:Enabled - // @Param: BLHAMPS_X - // @DisplayName: BLHAMPS_X + // @Param: ESCAMPS_X + // @DisplayName: ESCAMPS_X // @Description: Horizontal position on screen // @Range: 0 29 - // @Param: BLHAMPS_Y - // @DisplayName: BLHAMPS_Y + // @Param: ESCAMPS_Y + // @DisplayName: ESCAMPS_Y // @Description: Vertical position on screen // @Range: 0 15 - AP_SUBGROUPINFO(blh_amps, "BLHAMPS", 23, AP_OSD_Screen, AP_OSD_Setting), + AP_SUBGROUPINFO(esc_amps, "ESCAMPS", 23, AP_OSD_Screen, AP_OSD_Setting), #endif // @Param: GPSLAT_EN // @DisplayName: GPSLAT_EN @@ -1623,7 +1623,7 @@ void AP_OSD_Screen::draw_vspeed(uint8_t x, uint8_t y) } #if HAL_WITH_ESC_TELEM -void AP_OSD_Screen::draw_blh_temp(uint8_t x, uint8_t y) +void AP_OSD_Screen::draw_esc_temp(uint8_t x, uint8_t y) { int16_t etemp; // first parameter is index into array of ESC's. Hardwire to zero (first) for now. @@ -1631,11 +1631,10 @@ void AP_OSD_Screen::draw_blh_temp(uint8_t x, uint8_t y) return; } - uint8_t esc_temp = uint8_t(etemp / 100); - backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, esc_temp), u_icon(TEMPERATURE)); + backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, etemp / 100), u_icon(TEMPERATURE)); } -void AP_OSD_Screen::draw_blh_rpm(uint8_t x, uint8_t y) +void AP_OSD_Screen::draw_esc_rpm(uint8_t x, uint8_t y) { float rpm; // first parameter is index into array of ESC's. Hardwire to zero (first) for now. @@ -1647,14 +1646,14 @@ void AP_OSD_Screen::draw_blh_rpm(uint8_t x, uint8_t y) backend->write(x, y, false, format, krpm, SYM_KILO, SYM_RPM); } -void AP_OSD_Screen::draw_blh_amps(uint8_t x, uint8_t y) +void AP_OSD_Screen::draw_esc_amps(uint8_t x, uint8_t y) { - float esc_amps; + float amps; // first parameter is index into array of ESC's. Hardwire to zero (first) for now. - if (!AP::esc_telem().get_current(0, esc_amps)) { + if (!AP::esc_telem().get_current(0, amps)) { return; } - backend->write(x, y, false, "%4.1f%c", esc_amps, SYM_AMP); + backend->write(x, y, false, "%4.1f%c", amps, SYM_AMP); } #endif @@ -2056,9 +2055,9 @@ void AP_OSD_Screen::draw(void) DRAW_SETTING(vtx_power); #if HAL_WITH_ESC_TELEM - DRAW_SETTING(blh_temp); - DRAW_SETTING(blh_rpm); - DRAW_SETTING(blh_amps); + DRAW_SETTING(esc_temp); + DRAW_SETTING(esc_rpm); + DRAW_SETTING(esc_amps); #endif DRAW_SETTING(gps_latitude);