Fix UAVCAN beep not started

This commit is contained in:
alexklimaj 2022-01-12 12:50:38 -07:00 committed by Daniel Agar
parent 0bb9cce1ce
commit cdb6a437a0
4 changed files with 16 additions and 7 deletions

View File

@ -41,14 +41,14 @@
#include <lib/circuit_breaker/circuit_breaker.h>
UavcanBeep::UavcanBeep(uavcan::INode &node) :
UavcanBeepController::UavcanBeepController(uavcan::INode &node) :
_beep_pub(node),
_timer(node)
{
_beep_pub.setPriority(uavcan::TransferPriority::MiddleLower);
}
int UavcanBeep::init()
int UavcanBeepController::init()
{
// don't initialize if CBRK_BUZZER circuit breaker is enabled.
if (circuit_breaker_enabled("CBRK_BUZZER", CBRK_BUZZER_KEY)) {
@ -59,14 +59,14 @@ int UavcanBeep::init()
* Setup timer and call back function for periodic updates
*/
if (!_timer.isRunning()) {
_timer.setCallback(TimerCbBinder(this, &UavcanBeep::periodic_update));
_timer.setCallback(TimerCbBinder(this, &UavcanBeepController::periodic_update));
_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ));
}
return 0;
}
void UavcanBeep::periodic_update(const uavcan::TimerEvent &)
void UavcanBeepController::periodic_update(const uavcan::TimerEvent &)
{
if (_tune_control_sub.updated()) {
_tune_control_sub.copy(&_tune);

View File

@ -48,10 +48,10 @@
#include <uORB/topics/tune_control.h>
#include <lib/tunes/tunes.h>
class UavcanBeep
class UavcanBeepController
{
public:
UavcanBeep(uavcan::INode &node);
UavcanBeepController(uavcan::INode &node);
/*
* setup periodic updater
@ -69,7 +69,8 @@ private:
*/
void periodic_update(const uavcan::TimerEvent &);
typedef uavcan::MethodBinder<UavcanBeep *, void (UavcanBeep::*)(const uavcan::TimerEvent &)> TimerCbBinder;
typedef uavcan::MethodBinder<UavcanBeepController *, void (UavcanBeepController::*)(const uavcan::TimerEvent &)>
TimerCbBinder;
/*
* Subscription tune_control

View File

@ -81,6 +81,7 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::uavcan),
ModuleParams(nullptr),
_node(can_driver, system_clock, _pool_allocator),
_beep_controller(_node),
_esc_controller(_node),
_servo_controller(_node),
_hardpoint_controller(_node),
@ -506,6 +507,12 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events)
fill_node_info();
ret = _beep_controller.init();
if (ret < 0) {
return ret;
}
// Actuators
ret = _esc_controller.init();

View File

@ -226,6 +226,7 @@ private:
uavcan::Node<> _node; ///< library instance
pthread_mutex_t _node_mutex;
UavcanBeepController _beep_controller;
UavcanEscController _esc_controller;
UavcanServoController _servo_controller;
UavcanMixingInterfaceESC _mixing_interface_esc{_node_mutex, _esc_controller};