get node health and info

This commit is contained in:
ttechnick 2026-02-05 15:04:01 +01:00 committed by Nick
parent e756574420
commit 89c4980e55
2 changed files with 29 additions and 3 deletions

View File

@ -48,7 +48,8 @@ using namespace time_literals;
UavcanEscController::UavcanEscController(uavcan::INode &node) :
_node(node),
_uavcan_pub_raw_cmd(node),
_uavcan_sub_status(node)
_uavcan_sub_status(node),
_uavcan_sub_status_extended(node)
{
_uavcan_pub_raw_cmd.setPriority(uavcan::TransferPriority::NumericallyMin); // Highest priority
}
@ -64,6 +65,14 @@ UavcanEscController::init()
return res;
}
//ESC Status Extended subscription
res = _uavcan_sub_status_extended.start(StatusExtendedCbBinder(this, &UavcanEscController::esc_status_extended_sub_cb));
if (res < 0) {
PX4_ERR("ESC status extended sub failed %i", res);
return res;
}
_esc_status_pub.advertise();
int32_t iface_mask{0xFF};

View File

@ -47,9 +47,17 @@
#include <uavcan/uavcan.hpp>
#include <uavcan/equipment/esc/RawCommand.hpp>
#include <uavcan/equipment/esc/Status.hpp>
#include <uavcan/equipment/esc/StatusExtended.hpp>
#include <lib/perf/perf_counter.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/esc_status.h>
#include "../node_info.hpp"
#include <uORB/topics/esc_report.h>
#include <uORB/topics/dronecan_node_status.h>
#include <uORB/topics/device_information.h>
#include <drivers/drv_hrt.h>
#include <drivers/uavcan/node_info.hpp>
class UavcanEscController
{
@ -67,7 +75,7 @@ public:
bool initialized() { return _initialized; };
void update_outputs(uint16_t outputs[MAX_ACTUATORS], uint8_t output_array_size);
void update_outputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], uint8_t output_array_size);
/**
* Sets the number of rotors and enable timer
@ -85,6 +93,10 @@ private:
* ESC status message reception will be reported via this callback.
*/
void esc_status_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status> &msg);
/**
* ESC extended status message reception will be stored via this callback.
*/
void esc_status_extended_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::StatusExtended> &msg);
/**
* Checks all the ESCs freshness based on timestamp, if an ESC exceeds the timeout then is flagged offline.
@ -94,6 +106,10 @@ private:
typedef uavcan::MethodBinder<UavcanEscController *,
void (UavcanEscController::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&)> StatusCbBinder;
typedef uavcan::MethodBinder<UavcanEscController *,
void (UavcanEscController::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::StatusExtended>&)>
StatusExtendedCbBinder;
typedef uavcan::MethodBinder<UavcanEscController *,
void (UavcanEscController::*)(const uavcan::TimerEvent &)> TimerCbBinder;
@ -112,6 +128,7 @@ private:
uavcan::INode &_node;
uavcan::Publisher<uavcan::equipment::esc::RawCommand> _uavcan_pub_raw_cmd;
uavcan::Subscriber<uavcan::equipment::esc::Status, StatusCbBinder> _uavcan_sub_status;
uavcan::Subscriber<uavcan::equipment::esc::StatusExtended, StatusExtendedCbBinder> _uavcan_sub_status_extended;
NodeInfoPublisher *_node_info_publisher{nullptr};
};