Compare commits

...

1 Commits

Author SHA1 Message Date
Claudio Chies 109a5cb7c7 TRY1 2026-03-12 11:37:14 +01:00
7 changed files with 263 additions and 9 deletions
+58 -9
View File
@@ -128,7 +128,24 @@ void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<
_esc_status.counter += 1;
_esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_CAN;
_esc_status.esc_online_flags = check_escs_status();
_esc_status.esc_armed_flags = (1 << _rotor_count) - 1;
// Calculate esc_armed_flags: for Vertiq use status_flags bit 0, else assume armed
uint8_t armed_flags = 0;
for (uint8_t i = 0; i < _rotor_count; i++) {
if (detect_esc_manufacturer(i) == EscManufacturer::VERTIQ) {
if (_esc_status_flags[i] & (1 << 0)) {// Vertiq: bit 0 of status_flags indicates armed state
armed_flags |= (1 << i);
}
} else {
// Non-Vertiq: assume armed (per existing behavior)
armed_flags |= (1 << i);
}
}
_esc_status.esc_armed_flags = armed_flags;
_esc_status.timestamp = esc_report.timestamp;
_esc_status_pub.publish(_esc_status);
}
@@ -150,6 +167,13 @@ void UavcanEscController::esc_status_extended_sub_cb(const uavcan::ReceivedDataS
// published with the non-extended esc::Status
esc_report.motor_temperature = msg.motor_temperature_degC;
esc_report.esc_power = msg.input_pct;
// Store status_flags (use only first 8 bits)
_esc_status_flags[index] = static_cast<uint8_t>(msg.status_flags & 0xFF);
esc_report.esc_state = _esc_status_flags[index];
// Trigger manufacturer detection and caching
detect_esc_manufacturer(index);
}
}
@@ -169,9 +193,39 @@ uint8_t UavcanEscController::check_escs_status()
return esc_status_flags;
}
EscManufacturer UavcanEscController::detect_esc_manufacturer(uint8_t esc_index)
{
if (esc_index >= esc_status_s::CONNECTED_ESC_MAX) {
return EscManufacturer::UNKNOWN;
}
// Return cached value if already detected
if (_esc_manufacturer[esc_index] != EscManufacturer::NONE) {
return _esc_manufacturer[esc_index];
}
// Attempt to detect manufacturer from device_info
device_information_s device_info{};
if (_device_information_sub.copy(&device_info)
&& device_info.device_type == device_information_s::DEVICE_TYPE_ESC
&& device_info.device_id == esc_index) {
if (strstr(device_info.name, "iq_motion") != nullptr) {
_esc_manufacturer[esc_index] = EscManufacturer::VERTIQ;
} else {
// Detected but unrecognized manufacturer
_esc_manufacturer[esc_index] = EscManufacturer::UNKNOWN;
}
}
return _esc_manufacturer[esc_index];
}
uint32_t UavcanEscController::get_failures(uint8_t esc_index)
{
// Check DoneCAN node health of the ESC
// Check DroneCAN node health of the ESC
dronecan_node_status_s node_status{};
uint8_t esc_node_id = _esc_status.esc[esc_index].esc_address;
uint8_t node_health = dronecan_node_status_s::HEALTH_OK;
@@ -194,13 +248,8 @@ uint32_t UavcanEscController::get_failures(uint8_t esc_index)
return 0;
}
// Parse VertiQ = iq_motion ESC error flags
device_information_s device_information{};
if (_device_information_sub.copy(&device_information)
&& device_information.device_type == device_information_s::DEVICE_TYPE_ESC
&& device_information.device_id == esc_index
&& strstr(device_information.name, "iq_motion") != nullptr) {
// Parse Vertiq (iq_motion) ESC error flags using cached manufacturer
if (detect_esc_manufacturer(esc_index) == EscManufacturer::VERTIQ) {
static const struct {
uint8_t bit;
uint8_t failure_type;
+18
View File
@@ -57,6 +57,16 @@
#include <uORB/topics/dronecan_node_status.h>
#include "../node_info.hpp"
/**
* ESC manufacturer enumeration for vendor-specific handling
*/
enum class EscManufacturer : uint8_t {
NONE = 0, // Not yet detected (default)
UNKNOWN, // Detected but unrecognized manufacturer
VERTIQ, // iq_motion
// Future: TMOTOR, HOLYBRO, etc.
};
class UavcanEscController
{
public:
@@ -106,6 +116,11 @@ private:
*/
uint32_t get_failures(uint8_t esc_index);
/**
* Detects and caches the ESC manufacturer based on device_info name
*/
EscManufacturer detect_esc_manufacturer(uint8_t esc_index);
typedef uavcan::MethodBinder<UavcanEscController *,
void (UavcanEscController::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&)> StatusCbBinder;
@@ -125,6 +140,9 @@ private:
uint8_t _rotor_count{0};
EscManufacturer _esc_manufacturer[esc_status_s::CONNECTED_ESC_MAX] {}; // Cached manufacturer per ESC
uint8_t _esc_status_flags[esc_status_s::CONNECTED_ESC_MAX] {}; // StatusExtended status_flags per ESC
/*
* libuavcan related things
*/
+1
View File
@@ -49,6 +49,7 @@ px4_add_module(
calibration_routines.cpp
Commander.cpp
commander_helper.cpp
DisarmChecks.cpp
esc_calibration.cpp
factory_calibration_storage.cpp
gyro_calibration.cpp
+6
View File
@@ -709,6 +709,9 @@ transition_result_t Commander::disarm(arm_disarm_reason_t calling_reason, bool f
_user_mode_intention.onDisarm();
// Trigger disarm checks
_disarm_checks.start();
mavlink_log_info(&_mavlink_log_pub, "Disarmed by %s\t", arm_disarm_reason_str(calling_reason));
events::send<events::px4::enums::arm_disarm_reason_t>(events::ID("commander_disarmed_by"), events::Log::Info,
"Disarmed by {1}", calling_reason);
@@ -1916,6 +1919,9 @@ void Commander::run()
battery_status_check();
// Disarm checks
_disarm_checks.update(&_mavlink_log_pub);
checkForMissionUpdate();
manualControlCheck();
+3
View File
@@ -34,6 +34,7 @@
#pragma once
/* Helper classes */
#include "DisarmChecks.hpp"
#include "failsafe/failsafe.h"
#include "failure_detector/FailureDetector.hpp"
#include "HealthAndArmingChecks/HealthAndArmingChecks.hpp"
@@ -287,6 +288,8 @@ private:
bool _status_changed{true};
bool _mission_in_progress{false};
DisarmChecks _disarm_checks{};
vehicle_land_detected_s _vehicle_land_detected{};
// commander publications
+87
View File
@@ -0,0 +1,87 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file DisarmChecks.cpp
*/
#include "DisarmChecks.hpp"
#include "commander_helper.h"
#include <px4_platform_common/log.h>
#include <px4_platform_common/events.h>
void DisarmChecks::start()
{
_pending = true;
_deadline = hrt_absolute_time() + TIMEOUT;
}
void DisarmChecks::update(orb_advert_t *mavlink_log_pub)
{
if (!_pending) {
return;
}
if (hrt_absolute_time() >= _deadline) {
_pending = false;
// Run all verification checks at timeout
if (!checkEscDisarmed()) {
if (mavlink_log_pub) {
mavlink_log_critical(mavlink_log_pub, "ESC disarm failure: ESCs still armed\t");
}
events::send(events::ID("commander_esc_disarm_failure"),
{events::Log::Error, events::LogInternal::Warning},
"ESC disarm failure: one or more ESCs failed to disarm");
tune_negative(true);
}
// Future checks:
// if (!checkParachuteDisarmed()) { ... }
}
}
bool DisarmChecks::checkEscDisarmed()
{
esc_status_s esc_status;
if (_esc_status_sub.copy(&esc_status)) {
return esc_status.esc_armed_flags == 0;
}
// No ESC status data available - assume OK
return true;
}
+90
View File
@@ -0,0 +1,90 @@
/****************************************************************************
*
* Copyright (c) 2026 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file DisarmChecks.hpp
*
* Helper class to verify that components transition to disarmed state
* after the flight controller disarms.
*/
#pragma once
#include <px4_platform_common/defines.h>
#include <px4_platform_common/time.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/esc_status.h>
using namespace time_literals;
class DisarmChecks
{
public:
DisarmChecks() = default;
~DisarmChecks() = default;
/**
* Start the disarm verification process.
* Call this immediately after disarming.
*/
void start();
/**
* Update the verification state and report failures.
* Call this periodically from the main loop.
* @param mavlink_log_pub mavlink log publisher for console messages
*/
void update(orb_advert_t *mavlink_log_pub);
/**
* Check if verification is still pending.
*/
bool isPending() const { return _pending; }
private:
static constexpr hrt_abstime TIMEOUT{1_s};
/**
* Check if all ESCs have disarmed.
* @return true if all ESCs are disarmed (or no data available)
*/
bool checkEscDisarmed();
// Future checks can be added here:
// bool checkParachuteDisarmed();
bool _pending{false};
hrt_abstime _deadline{0};
uORB::Subscription _esc_status_sub{ORB_ID(esc_status)};
};