Classes | Typedefs | Enumerations | Functions | Variables
uavcan_linux Namespace Reference

Classes

class  AllIfacesDownException
 
class  BlockingServiceClient
 
class  DefaultLogSink
 
struct  DriverPack
 
class  Exception
 
class  LibuavcanErrorException
 
class  MachineIDReader
 
class  Node
 
class  NodeBase
 
class  SocketCanDriver
 
class  SocketCanIface
 
class  SubNode
 
class  SystemClock
 

Typedefs

template<typename T >
using BlockingServiceClientPtr = std::shared_ptr< BlockingServiceClient< T > >
 
typedef std::shared_ptr< DriverPackDriverPackPtr
 
typedef std::shared_ptr< uavcan::INodeINodePtr
 
typedef std::shared_ptr< NodeNodePtr
 
template<typename T >
using PublisherPtr = std::shared_ptr< uavcan::Publisher< T > >
 
template<typename T >
using ServiceClientPtr = std::shared_ptr< uavcan::ServiceClient< T > >
 
template<typename T >
using ServiceServerPtr = std::shared_ptr< uavcan::ServiceServer< T > >
 
typedef std::shared_ptr< SubNodeSubNodePtr
 
template<typename T >
using SubscriberPtr = std::shared_ptr< uavcan::Subscriber< T > >
 
typedef std::shared_ptr< uavcan::TimerTimerPtr
 

Enumerations

enum  ClockAdjustmentMode { ClockAdjustmentMode::SystemWide, ClockAdjustmentMode::PerDriverPrivate }
 
enum  SocketCanError { SocketCanError::SocketReadFailure, SocketCanError::SocketWriteFailure, SocketCanError::TxTimeout }
 

Functions

std::array< std::uint8_t, 16 > makeApplicationID (const MachineIDReader::MachineID &machine_id, const std::string &node_name, const std::uint8_t instance_id=0)
 
template<typename DriverType >
static NodePtr makeNode (const DriverType &driver, const uavcan::NodeStatusProvider::NodeName &name, const uavcan::protocol::SoftwareVersion &software_version, const uavcan::protocol::HardwareVersion &hardware_version, const uavcan::NodeID node_id=uavcan::NodeID(), const uavcan::TransferPriority node_status_transfer_priority=uavcan::TransferPriority::Default, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
 
static NodePtr makeNode (const std::shared_ptr< uavcan::ICanDriver > &can_driver, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
 
static NodePtr makeNode (const std::vector< std::string > &iface_names, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
 
template<typename DriverType >
static SubNodePtr makeSubNode (const DriverType &driver, const uavcan::NodeID node_id, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
 
static SubNodePtr makeSubNode (const std::shared_ptr< uavcan::ICanDriver > &can_driver, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
 
static SubNodePtr makeSubNode (const std::vector< std::string > &iface_names, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
 

Variables

static constexpr std::size_t NodeMemPoolSize = 1024 * 512
 This shall be enough for any possible use case. More...
 

Typedef Documentation

◆ BlockingServiceClientPtr

template<typename T >
using uavcan_linux::BlockingServiceClientPtr = typedef std::shared_ptr<BlockingServiceClient<T> >

◆ DriverPackPtr

typedef std::shared_ptr<DriverPack> uavcan_linux::DriverPackPtr

◆ INodePtr

typedef std::shared_ptr<uavcan::INode> uavcan_linux::INodePtr

◆ NodePtr

typedef std::shared_ptr<Node> uavcan_linux::NodePtr

◆ PublisherPtr

template<typename T >
using uavcan_linux::PublisherPtr = typedef std::shared_ptr<uavcan::Publisher<T> >

◆ ServiceClientPtr

template<typename T >
using uavcan_linux::ServiceClientPtr = typedef std::shared_ptr<uavcan::ServiceClient<T> >

◆ ServiceServerPtr

template<typename T >
using uavcan_linux::ServiceServerPtr = typedef std::shared_ptr<uavcan::ServiceServer<T> >

◆ SubNodePtr

typedef std::shared_ptr<SubNode> uavcan_linux::SubNodePtr

◆ SubscriberPtr

template<typename T >
using uavcan_linux::SubscriberPtr = typedef std::shared_ptr<uavcan::Subscriber<T> >

◆ TimerPtr

typedef std::shared_ptr<uavcan::Timer> uavcan_linux::TimerPtr

Enumeration Type Documentation

◆ ClockAdjustmentMode

Different adjustment modes can be used for time synchronization

Enumerator
SystemWide 

Adjust the clock globally for the whole system; requires root privileges.

PerDriverPrivate 

Adjust the clock only for the current driver instance.

Definition at line 23 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/clock.hpp.

◆ SocketCanError

SocketCan driver class keeps number of each kind of errors occurred since the object was created.

Enumerator
SocketReadFailure 
SocketWriteFailure 
TxTimeout 

Definition at line 35 of file socketcan.hpp.

Function Documentation

◆ makeApplicationID()

std::array<std::uint8_t, 16> uavcan_linux::makeApplicationID ( const MachineIDReader::MachineID machine_id,
const std::string &  node_name,
const std::uint8_t  instance_id = 0 
)
inline

This class computes unique ID for a UAVCAN node in a Linux application. It takes the following inputs:

  • Unique machine ID
  • Node name string (e.g. "org.uavcan.linux_app.dynamic_node_id_server")
  • Instance ID byte, e.g. node ID (optional)

Definition at line 143 of file system_utils.hpp.

◆ makeNode() [1/3]

template<typename DriverType >
static NodePtr uavcan_linux::makeNode ( const DriverType &  driver,
const uavcan::NodeStatusProvider::NodeName name,
const uavcan::protocol::SoftwareVersion &  software_version,
const uavcan::protocol::HardwareVersion &  hardware_version,
const uavcan::NodeID  node_id = uavcan::NodeID(),
const uavcan::TransferPriority  node_status_transfer_priority = uavcan::TransferPriority::Default,
ClockAdjustmentMode  clock_adjustment_mode = SystemClock::detectPreferredClockAdjustmentMode() 
)
inlinestatic

This function extends the other two overloads in such a way that it instantiates and initializes the node immediately; if initialization fails, it throws.

If NodeID is not provided, it will not be initialized, and therefore the node will be started in listen-only (i.e. silent) mode. The node can be switched to normal (i.e. non-silent) mode at any later time by calling setNodeID() explicitly. Read the Node class docs for more info.

Clock adjustment mode will be detected automatically unless provided explicitly.

Exceptions
uavcan_linux::Exception,uavcan_linux::LibuavcanErrorException.

Definition at line 397 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp.

◆ makeNode() [2/3]

static NodePtr uavcan_linux::makeNode ( const std::shared_ptr< uavcan::ICanDriver > &  can_driver,
ClockAdjustmentMode  clock_adjustment_mode = SystemClock::detectPreferredClockAdjustmentMode() 
)
inlinestatic

Use this function to create a node instance with a custom driver. Clock adjustment mode will be detected automatically unless provided explicitly.

Exceptions
uavcan_linux::Exception.

Definition at line 376 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp.

◆ makeNode() [3/3]

static NodePtr uavcan_linux::makeNode ( const std::vector< std::string > &  iface_names,
ClockAdjustmentMode  clock_adjustment_mode = SystemClock::detectPreferredClockAdjustmentMode() 
)
inlinestatic

Use this function to create a node instance with default SocketCAN driver. It accepts the list of interface names to use for the new node, e.g. "can1", "vcan2", "slcan0". Clock adjustment mode will be detected automatically unless provided explicitly.

Exceptions
uavcan_linux::Exception.

Definition at line 363 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp.

◆ makeSubNode() [1/3]

template<typename DriverType >
static SubNodePtr uavcan_linux::makeSubNode ( const DriverType &  driver,
const uavcan::NodeID  node_id,
ClockAdjustmentMode  clock_adjustment_mode = SystemClock::detectPreferredClockAdjustmentMode() 
)
inlinestatic

This function extends the other two overloads in such a way that it instantiates the node and sets its Node ID immediately.

Clock adjustment mode will be detected automatically unless provided explicitly.

Exceptions
uavcan_linux::Exception,uavcan_linux::LibuavcanErrorException.

Definition at line 463 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp.

◆ makeSubNode() [2/3]

static SubNodePtr uavcan_linux::makeSubNode ( const std::shared_ptr< uavcan::ICanDriver > &  can_driver,
ClockAdjustmentMode  clock_adjustment_mode = SystemClock::detectPreferredClockAdjustmentMode() 
)
inlinestatic

Use this function to create a sub-node instance with a custom driver. Clock adjustment mode will be detected automatically unless provided explicitly.

Exceptions
uavcan_linux::Exception.

Definition at line 446 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp.

◆ makeSubNode() [3/3]

static SubNodePtr uavcan_linux::makeSubNode ( const std::vector< std::string > &  iface_names,
ClockAdjustmentMode  clock_adjustment_mode = SystemClock::detectPreferredClockAdjustmentMode() 
)
inlinestatic

Use this function to create a sub-node instance with default SocketCAN driver. It accepts the list of interface names to use for the new node, e.g. "can1", "vcan2", "slcan0". Clock adjustment mode will be detected automatically unless provided explicitly.

Exceptions
uavcan_linux::Exception.

Definition at line 433 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp.

Variable Documentation

◆ NodeMemPoolSize

constexpr std::size_t uavcan_linux::NodeMemPoolSize = 1024 * 512
staticconstexpr

This shall be enough for any possible use case.

Definition at line 164 of file platform_specific_components/linux/libuavcan/include/uavcan_linux/helpers.hpp.



uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:05