Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

BLHeli: fixed build without BLHeli with sim on hw #26122

Merged
merged 7 commits into from
Mar 18, 2024
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/AP_BLHeli/AP_BLHeli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include "AP_BLHeli.h"

#ifdef HAVE_AP_BLHELI_SUPPORT
#if HAVE_AP_BLHELI_SUPPORT

#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <hal.h>
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_BLHeli/AP_BLHeli.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>

#if HAL_SUPPORT_RCOUT_SERIAL
#define HAVE_AP_BLHELI_SUPPORT HAL_SUPPORT_RCOUT_SERIAL

#define HAVE_AP_BLHELI_SUPPORT
#if HAL_SUPPORT_RCOUT_SERIAL

#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>

Expand Down
7 changes: 6 additions & 1 deletion libraries/AP_IOMCU/AP_IOMCU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_BLHeli/AP_BLHeli.h>
#include <ch.h>

extern const AP_HAL::HAL &hal;
Expand Down Expand Up @@ -118,11 +119,13 @@ void AP_IOMCU::thread_main(void)
uart.set_unbuffered_writes(true);

#if HAL_WITH_IO_MCU_BIDIR_DSHOT
AP_BLHeli* blh = AP_BLHeli::get_singleton();
uint16_t erpm_period_ms = 10; // default 100Hz
#if HAVE_AP_BLHELI_SUPPORT
AP_BLHeli* blh = AP_BLHeli::get_singleton();
if (blh && blh->get_telemetry_rate() > 0) {
erpm_period_ms = constrain_int16(1000 / blh->get_telemetry_rate(), 1, 1000);
}
#endif
#endif
trigger_event(IOEVENT_INIT);

Expand Down Expand Up @@ -409,10 +412,12 @@ void AP_IOMCU::read_erpm()
return;
}
uint8_t motor_poles = 14;
#if HAVE_AP_BLHELI_SUPPORT
AP_BLHeli* blh = AP_BLHeli::get_singleton();
if (blh) {
motor_poles = blh->get_motor_poles();
}
#endif
for (uint8_t i = 0; i < IOMCU_MAX_TELEM_CHANNELS/4; i++) {
for (uint8_t j = 0; j < 4; j++) {
const uint8_t esc_id = (i * 4 + j);
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_OSD/AP_OSD_MSP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = {
{ "OSD_VSPEED_X", 1.0 },
{ "OSD_VSPEED_Y", 1.0 },

#ifdef HAVE_AP_BLHELI_SUPPORT
#if HAVE_AP_BLHELI_SUPPORT
//OSD_ESC_TMP
{ "OSD_BLHTEMP_EN", 1.0 },
{ "OSD_BLHTEMP_X", 1.0 },
Expand Down Expand Up @@ -180,4 +180,4 @@ AP_OSD_Backend *AP_OSD_MSP::probe(AP_OSD &osd)
return nullptr;
}
return backend;
}
}
26 changes: 7 additions & 19 deletions libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,7 @@
#include <AP_Baro/AP_Baro.h>
#include <AP_RTC/AP_RTC.h>
#include <AP_SerialManager/AP_SerialManager.h>
#ifdef HAVE_AP_BLHELI_SUPPORT
#include <AP_BLheli/AP_BLHeli.h>
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

don't you need a define guard in the header if you do this?

#endif
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#include <math.h>

#if HAL_SPEKTRUM_TELEM_ENABLED
Expand Down Expand Up @@ -579,25 +577,15 @@ void AP_Spektrum_Telem::calc_gps_status()
// prepare ESC information - B/E
void AP_Spektrum_Telem::calc_esc()
{
#ifdef HAVE_AP_BLHELI_SUPPORT
AP_BLHeli* blh = AP_BLHeli::get_singleton();

if (blh == nullptr) {
return;
}

AP_BLHeli::telem_data td;

if (!blh->get_telem_data(0, td)) {
return;
}
#if HAL_WITH_ESC_TELEM
const volatile AP_ESC_Telem_Backend::TelemetryData& td = AP::esc_telem().get_telem_data(0); // ideally should rotate between ESCs

_telem.esc.identifier = TELE_DEVICE_ESC; // Source device = 0x20
_telem.esc.sID = 0; // Secondary ID
_telem.esc.RPM = htobe16(uint16_t(roundf(blh->get_average_motor_frequency_hz() * 60))); // Electrical RPM, 10RPM (0-655340 RPM) 0xFFFF --> "No data"
_telem.esc.voltsInput = htobe16(td.voltage); // Volts, 0.01v (0-655.34V) 0xFFFF --> "No data"
_telem.esc.tempFET = htobe16(td.temperature * 10); // Temperature, 0.1C (0-6553.4C) 0xFFFF --> "No data"
_telem.esc.currentMotor = htobe16(td.current); // Current, 10mA (0-655.34A) 0xFFFF --> "No data"
_telem.esc.RPM = htobe16(uint16_t(roundf(AP::esc_telem().get_average_motor_frequency_hz() * 60))); // Electrical RPM, 10RPM (0-655340 RPM) 0xFFFF --> "No data"
_telem.esc.voltsInput = htobe16(td.voltage * 100); // Volts, 0.01v (0-655.34V) 0xFFFF --> "No data"
_telem.esc.tempFET = htobe16(td.temperature_cdeg * 10); // Temperature, 0.1C (0-6553.4C) 0xFFFF --> "No data"
_telem.esc.currentMotor = htobe16(td.current * 100); // Current, 10mA (0-655.34A) 0xFFFF --> "No data"
_telem.esc.tempBEC = 0xFFFF; // Temperature, 0.1C (0-6553.4C) 0xFFFF --> "No data"
_telem.esc.currentBEC = 0xFF; // BEC Current, 100mA (0-25.4A) 0xFF ----> "No data"
_telem.esc.voltsBEC = 0xFF; // BEC Volts, 0.05V (0-12.70V) 0xFF ----> "No data"
Expand Down
Loading