PX4 Firmware
PX4 Autopilot Software http://px4.io
UavcanEsc Class Reference

A UAVCAN node. More...

#include <uavcanesc_main.hpp>

Inheritance diagram for UavcanEsc:
Collaboration diagram for UavcanEsc:

Public Types

typedef uavcan::Node< MemPoolSizeNode
 
typedef uavcan_stm32::CanInitHelper< RxQueueLenPerIfaceCanInitHelper
 
typedef uavcan::protocol::file::BeginFirmwareUpdate BeginFirmwareUpdate
 

Public Member Functions

 UavcanEsc (uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock)
 
virtual ~UavcanEsc ()
 
virtual int ioctl (file *filp, int cmd, unsigned long arg)
 
Nodeget_node ()
 
int teardown ()
 
void print_info ()
 
- Public Member Functions inherited from cdev::CDev
 CDev (const char *devname)
 Constructor. More...
 
 CDev (const CDev &)=delete
 
CDevoperator= (const CDev &)=delete
 
 CDev (CDev &&)=delete
 
CDevoperator= (CDev &&)=delete
 
virtual ~CDev ()
 
virtual int init ()
 
virtual int open (file_t *filep)
 Handle an open of the device. More...
 
virtual int close (file_t *filep)
 Handle a close of the device. More...
 
virtual ssize_t read (file_t *filep, char *buffer, size_t buflen)
 Perform a read from the device. More...
 
virtual ssize_t write (file_t *filep, const char *buffer, size_t buflen)
 Perform a write to the device. More...
 
virtual off_t seek (file_t *filep, off_t offset, int whence)
 Perform a logical seek operation on the device. More...
 
virtual int ioctl (file_t *filep, int cmd, unsigned long arg)
 Perform an ioctl operation on the device. More...
 
virtual int poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup)
 Perform a poll setup/teardown operation. More...
 
const char * get_devname () const
 Get the device name. More...
 

Static Public Member Functions

static int start (uavcan::NodeID node_id, uint32_t bitrate)
 
static UavcanEscinstance ()
 

Public Attributes

int32_t active_bitrate
 
uavcan::TimerEventForwarder< void(*)(const uavcan::TimerEvent &)> _reset_timer
 

Private Types

typedef uavcan::MethodBinder< UavcanEsc *, void(UavcanEsc::*)(const uavcan::ReceivedDataStructure< UavcanEsc::BeginFirmwareUpdate::Request > &, uavcan::ServiceResponseDataStructure< UavcanEsc::BeginFirmwareUpdate::Response > &)> BeginFirmwareUpdateCallBack
 

Private Member Functions

void fill_node_info ()
 
int init (uavcan::NodeID node_id, uavcan_stm32::BusEvent &bus_events)
 
void node_spin_once ()
 
int run ()
 
void cb_beginfirmware_update (const uavcan::ReceivedDataStructure< UavcanEsc::BeginFirmwareUpdate::Request > &req, uavcan::ServiceResponseDataStructure< UavcanEsc::BeginFirmwareUpdate::Response > &rsp)
 

Static Private Member Functions

static void busevent_signal_trampoline ()
 

Private Attributes

px4_sem_t _sem
 semaphore for scheduling the task More...
 
int _task = -1
 handle to the OS task More...
 
bool _task_should_exit = false
 flag to indicate to tear down the CAN driver More...
 
Node _node
 library instance More...
 
pthread_mutex_t _node_mutex
 
uavcan::ServiceServer< BeginFirmwareUpdate, BeginFirmwareUpdateCallBack_fw_update_listner
 

Static Private Attributes

static constexpr unsigned MemPoolSize = 2048
 
static constexpr unsigned RxQueueLenPerIface = 5
 
static constexpr unsigned StackSize = 4096
 
static UavcanEsc_instance
 singleton pointer More...
 

Additional Inherited Members

- Protected Member Functions inherited from cdev::CDev
virtual pollevent_t poll_state (file_t *filep)
 Check the current state of the device for poll events from the perspective of the file. More...
 
virtual void poll_notify (pollevent_t events)
 Report new poll events. More...
 
virtual void poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events)
 Internal implementation of poll_notify. More...
 
virtual int open_first (file_t *filep)
 Notification of the first open. More...
 
virtual int close_last (file_t *filep)
 Notification of the last close. More...
 
virtual int register_class_devname (const char *class_devname)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
virtual int unregister_class_devname (const char *class_devname, unsigned class_instance)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
void lock ()
 Take the driver lock. More...
 
void unlock ()
 Release the driver lock. More...
 
int unregister_driver_and_memory ()
 First, unregisters the driver. More...
 
- Protected Attributes inherited from cdev::CDev
px4_sem_t _lock
 lock to protect access to all class members (also for derived classes) More...
 
- Static Protected Attributes inherited from cdev::CDev
static const px4_file_operations_t fops = {}
 Pointer to the default cdev file operations table; useful for registering clone devices etc. More...
 

Detailed Description

A UAVCAN node.

Definition at line 57 of file uavcanesc_main.hpp.

Member Typedef Documentation

◆ BeginFirmwareUpdate

typedef uavcan::protocol::file::BeginFirmwareUpdate UavcanEsc::BeginFirmwareUpdate

Definition at line 92 of file uavcanesc_main.hpp.

◆ BeginFirmwareUpdateCallBack

typedef uavcan::MethodBinder<UavcanEsc *, void (UavcanEsc::*)(const uavcan::ReceivedDataStructure<UavcanEsc::BeginFirmwareUpdate::Request> &, uavcan::ServiceResponseDataStructure<UavcanEsc::BeginFirmwareUpdate::Response> &)> UavcanEsc::BeginFirmwareUpdateCallBack
private

Definition at line 135 of file uavcanesc_main.hpp.

◆ CanInitHelper

◆ Node

typedef uavcan::Node<MemPoolSize> UavcanEsc::Node

Definition at line 90 of file uavcanesc_main.hpp.

Constructor & Destructor Documentation

◆ UavcanEsc()

UavcanEsc::UavcanEsc ( uavcan::ICanDriver &  can_driver,
uavcan::ISystemClock &  system_clock 
)

Definition at line 90 of file uavcanesc_main.cpp.

References _node_mutex, and _sem.

Referenced by start().

Here is the caller graph for this function:

◆ ~UavcanEsc()

UavcanEsc::~UavcanEsc ( )
virtual

Definition at line 110 of file uavcanesc_main.cpp.

References _instance, _sem, _task, and _task_should_exit.

Member Function Documentation

◆ busevent_signal_trampoline()

void UavcanEsc::busevent_signal_trampoline ( )
staticprivate

Definition at line 332 of file uavcanesc_main.cpp.

References _instance, _sem, and signal_callback().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ cb_beginfirmware_update()

void UavcanEsc::cb_beginfirmware_update ( const uavcan::ReceivedDataStructure< UavcanEsc::BeginFirmwareUpdate::Request > &  req,
uavcan::ServiceResponseDataStructure< UavcanEsc::BeginFirmwareUpdate::Response > &  rsp 
)
private

Definition at line 239 of file uavcanesc_main.cpp.

References _node, _reset_timer, active_bitrate, App, bootloader_app_shared_write(), bootloader_app_shared_t::bus_speed, cb_reboot(), bootloader_app_shared_t::node_id, and rgb_led().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fill_node_info()

void UavcanEsc::fill_node_info ( )
private

Definition at line 201 of file uavcanesc_main.cpp.

References _node, AppDescriptor, app_descriptor_t::image_crc, app_descriptor_t::major_version, app_descriptor_t::minor_version, and px4_firmware_version_string().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_node()

Node& UavcanEsc::get_node ( )
inline

Definition at line 102 of file uavcanesc_main.hpp.

References _node, print_info(), and teardown().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int UavcanEsc::init ( uavcan::NodeID  node_id,
uavcan_stm32::BusEvent &  bus_events 
)
private

Definition at line 264 of file uavcanesc_main.cpp.

References _fw_update_listner, _node, busevent_signal_trampoline(), cb_beginfirmware_update(), fill_node_info(), ToneAlarmInterface::init(), and OK.

Referenced by start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ instance()

static UavcanEsc* UavcanEsc::instance ( )
inlinestatic

Definition at line 108 of file uavcanesc_main.hpp.

References _instance.

Referenced by uavcanesc_main().

Here is the caller graph for this function:

◆ ioctl()

int UavcanEsc::ioctl ( file filp,
int  cmd,
unsigned long  arg 
)
virtual

Definition at line 386 of file uavcanesc_main.cpp.

References cdev::CDev::lock(), OK, and cdev::CDev::unlock().

Here is the call graph for this function:

◆ node_spin_once()

void UavcanEsc::node_spin_once ( )
private

Definition at line 308 of file uavcanesc_main.cpp.

References _node.

Referenced by run().

Here is the caller graph for this function:

◆ print_info()

void UavcanEsc::print_info ( void  )

Definition at line 411 of file uavcanesc_main.cpp.

References _instance, and _node_mutex.

Referenced by get_node(), and uavcanesc_main().

Here is the caller graph for this function:

◆ run()

int UavcanEsc::run ( )
private

Definition at line 339 of file uavcanesc_main.cpp.

References _node, _node_mutex, _sem, _task_should_exit, get_node(), hrt_call_every(), hrt_cancel(), init_indication_controller(), node_spin_once(), restart_request_handler, signal_callback(), and teardown().

Referenced by start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

int UavcanEsc::start ( uavcan::NodeID  node_id,
uint32_t  bitrate 
)
static

Definition at line 135 of file uavcanesc_main.cpp.

References _instance, _task, active_bitrate, uavcan_stm32::CanInitHelper< RxQueueCapacity >::driver, init(), uavcan_stm32::CanInitHelper< RxQueueCapacity >::init(), uavcan_stm32::SystemClock::instance(), OK, run(), StackSize, UavcanEsc(), and uavcan_stm32::CanDriver::updateEvent().

Referenced by uavcannode_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ teardown()

int UavcanEsc::teardown ( )

Definition at line 378 of file uavcanesc_main.cpp.

Referenced by get_node(), and run().

Here is the caller graph for this function:

Member Data Documentation

◆ _fw_update_listner

uavcan::ServiceServer<BeginFirmwareUpdate, BeginFirmwareUpdateCallBack> UavcanEsc::_fw_update_listner
private

Definition at line 137 of file uavcanesc_main.hpp.

Referenced by init().

◆ _instance

UavcanEsc * UavcanEsc::_instance
staticprivate

singleton pointer

Definition at line 128 of file uavcanesc_main.hpp.

Referenced by busevent_signal_trampoline(), instance(), print_info(), start(), and ~UavcanEsc().

◆ _node

Node UavcanEsc::_node
private

library instance

Definition at line 129 of file uavcanesc_main.hpp.

Referenced by cb_beginfirmware_update(), fill_node_info(), get_node(), init(), node_spin_once(), and run().

◆ _node_mutex

pthread_mutex_t UavcanEsc::_node_mutex
private

Definition at line 130 of file uavcanesc_main.hpp.

Referenced by print_info(), run(), and UavcanEsc().

◆ _reset_timer

uavcan::TimerEventForwarder<void (*)(const uavcan::TimerEvent &)> UavcanEsc::_reset_timer

Definition at line 145 of file uavcanesc_main.hpp.

Referenced by cb_beginfirmware_update().

◆ _sem

px4_sem_t UavcanEsc::_sem
private

semaphore for scheduling the task

Definition at line 124 of file uavcanesc_main.hpp.

Referenced by busevent_signal_trampoline(), run(), UavcanEsc(), and ~UavcanEsc().

◆ _task

int UavcanEsc::_task = -1
private

handle to the OS task

Definition at line 125 of file uavcanesc_main.hpp.

Referenced by start(), and ~UavcanEsc().

◆ _task_should_exit

bool UavcanEsc::_task_should_exit = false
private

flag to indicate to tear down the CAN driver

Definition at line 126 of file uavcanesc_main.hpp.

Referenced by run(), and ~UavcanEsc().

◆ active_bitrate

int32_t UavcanEsc::active_bitrate

Definition at line 113 of file uavcanesc_main.hpp.

Referenced by cb_beginfirmware_update(), and start().

◆ MemPoolSize

constexpr unsigned UavcanEsc::MemPoolSize = 2048
staticprivate

Definition at line 68 of file uavcanesc_main.hpp.

◆ RxQueueLenPerIface

constexpr unsigned UavcanEsc::RxQueueLenPerIface = 5
staticprivate

Definition at line 81 of file uavcanesc_main.hpp.

◆ StackSize

constexpr unsigned UavcanEsc::StackSize = 4096
staticprivate

Definition at line 87 of file uavcanesc_main.hpp.

Referenced by start().


The documentation for this class was generated from the following files: