fix ifdef, adjust esc isInRange check

This commit is contained in:
Jacob Dahl
2026-01-13 21:42:56 -09:00
parent 24d7cd48e5
commit 458c775bfd
2 changed files with 7 additions and 4 deletions
@@ -105,13 +105,12 @@ void EscChecks::checkEscStatus(const Context &context, Report &reporter, const e
const NavModes required_modes = _param_escs_checks_required.get() ? NavModes::All : NavModes::None;
if (esc_status.esc_count > 0) {
// Check if one or more the ESCs are offline
char esc_fail_msg[50];
esc_fail_msg[0] = '\0';
int online_bitmask = (1 << esc_status.esc_count) - 1;
// Check if one or more the ESCs are offline
if (online_bitmask != esc_status.esc_online_flags) {
for (int i = 0; i < esc_status_s::CONNECTED_ESC_MAX; i++) {
@@ -119,7 +118,7 @@ void EscChecks::checkEscStatus(const Context &context, Report &reporter, const e
uint8_t actuator_function = esc_status.esc[i].actuator_function;
bool is_motor = math::isInRange(actuator_function, actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1,
actuator_motors_s::ACTUATOR_FUNCTION_MOTOR12);
actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1 + actuator_motors_s::NUM_CONTROLS - 1);
bool is_online = esc_status.esc_online_flags & (1 << i);
if (is_motor && !is_online) {
+5 -1
View File
@@ -602,11 +602,15 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
uint16_t message_id = (uint16_t)roundf(vehicle_command.param1);
#if defined(MAVLINK_MSG_ID_ESC_EEPROM)
// NOTE: ESC_EEPROM message request handling is deferred - DShot driver handles and triggers reading
if (message_id == MAVLINK_MSG_ID_ESC_EEPROM) {
PX4_INFO("publishing MAV_CMD_REQUEST_MESSAGE for MAVLINK_MSG_ID_ESC_EEPROM");
_cmd_pub.publish(vehicle_command);
else
if (1)
// no-op
#endif
} else if (message_id == MAVLINK_MSG_ID_MESSAGE_INTERVAL) {
get_message_interval((int)(cmd_mavlink.param2 + 0.5f));