ros2_canopen  master
C++ ROS CANopen Library
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ros2_canopen::DeviceContainer Class Reference

Lifecycle Device Container for CANopen. More...

#include <device_container.hpp>

Inheritance diagram for ros2_canopen::DeviceContainer:
Inheritance graph
[legend]
Collaboration diagram for ros2_canopen::DeviceContainer:
Collaboration graph
[legend]

Public Member Functions

 DeviceContainer (std::weak_ptr< rclcpp::Executor > executor=std::weak_ptr< rclcpp::executors::MultiThreadedExecutor >(), std::string node_name="device_container", const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions())
 Construct a new Lifecycle Device Container Node object. More...
 
void init ()
 Executes the initialisation. More...
 
void init (const std::string &can_interface_name, const std::string &master_config, const std::string &bus_config, const std::string &master_bin="")
 Executes the initialisation. More...
 
virtual void configure ()
 
virtual bool load_drivers ()
 Loads drivers from configuration. More...
 
virtual bool load_master ()
 Loads master from configuration. More...
 
virtual bool load_manager ()
 Loads the device manager. More...
 
virtual bool load_component (std::string &package_name, std::string &driver_name, uint16_t node_id, std::string &node_name, std::vector< rclcpp::Parameter > &params)
 Load a component. More...
 
virtual void shutdown ()
 Shutdown all devices. More...
 
virtual void on_list_nodes (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< ListNodes::Request > request, std::shared_ptr< ListNodes::Response > response) override
 Callback for the listing service. More...
 
virtual std::map< uint16_t, std::shared_ptr< CanopenDriverInterface > > get_registered_drivers ()
 Get the registered drivers object. More...
 
virtual size_t count_drivers ()
 Get the number of registered drivers. More...
 
std::vector< uint16_t > get_ids_of_drivers_with_type (std::string type)
 Get node ids of all drivers with type. More...
 
std::string get_driver_type (uint16_t id)
 Get the type of driver by node id. More...
 

Protected Member Functions

void set_executor (const std::weak_ptr< rclcpp::Executor > executor)
 Set the ROS executor object. More...
 
bool init_driver (uint16_t node_id)
 Initialises a driver. More...
 
void on_init_driver (const canopen_interfaces::srv::CONode::Request::SharedPtr request, canopen_interfaces::srv::CONode::Response::SharedPtr response)
 Callback for init driver service. More...
 
std::map< uint16_t, std::string > list_components ()
 Returns a list of components. More...
 
virtual void add_node_to_executor (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_interface)
 Add node to executor. More...
 

Protected Attributes

std::map< uint16_t, std::shared_ptr< CanopenDriverInterface > > registered_drivers_
 Map of drivers registered in busconfiguration. Name is key. More...
 
std::shared_ptr< ros2_canopen::CanopenMasterInterfacecan_master_
 Pointer to can master instance. More...
 
uint16_t can_master_id_
 
std::unique_ptr< ros2_canopen::LifecycleManagerlifecycle_manager_
 
std::shared_ptr< ros2_canopen::ConfigurationManagerconfig_
 Pointer to configuration manager instance. More...
 
std::string dcf_txt_
 Cached value of .dcf file parameter. More...
 
std::string bus_config_
 Cached value of bus.yml file parameter. More...
 
std::string dcf_bin_
 Cached value of .bin file parameter. More...
 
std::string can_interface_name_
 Cached value of can interface name. More...
 
bool lifecycle_operation_
 
std::weak_ptr< rclcpp::Executor > executor_
 Pointer to ros executor instance. More...
 
rclcpp::Service< canopen_interfaces::srv::CONode >::SharedPtr init_driver_service_
 Service object for init_driver service. More...
 
rclcpp::CallbackGroup::SharedPtr client_cbg_
 Callback group for services. More...
 

Detailed Description

Lifecycle Device Container for CANopen.

This class provides the functionality for loading a the CANopen Master and CANopen Device Drivers based on the Configuration Files. Configuration files need to be passed in as parameters.

Constructor & Destructor Documentation

◆ DeviceContainer()

ros2_canopen::DeviceContainer::DeviceContainer ( std::weak_ptr< rclcpp::Executor >  executor = std::weak_ptr<rclcpp::executors::MultiThreadedExecutor>(),
std::string  node_name = "device_container",
const rclcpp::NodeOptions &  node_options = rclcpp::NodeOptions() 
)
inline

Construct a new Lifecycle Device Container Node object.

Parameters
[in]executorThe executor to add loaded master and devices to.
[in]node_nameThe name of the node
[in]node_optionsPassed to the device_container node

Member Function Documentation

◆ init() [1/2]

void ros2_canopen::DeviceContainer::init ( )

Executes the initialisation.

This will read nodes parameters and initialize the configuration defined in the parameters. It will also start loading the components.

Returns
true
false

◆ init() [2/2]

void ros2_canopen::DeviceContainer::init ( const std::string &  can_interface_name,
const std::string &  master_config,
const std::string &  bus_config,
const std::string &  master_bin = "" 
)

Executes the initialisation.

Same as init() only that ros parameters are not used.

Parameters
can_interface_name
master_config
bus_config
master_bin

◆ configure()

virtual void ros2_canopen::DeviceContainer::configure ( )
virtual

◆ load_drivers()

virtual bool ros2_canopen::DeviceContainer::load_drivers ( )
virtual

Loads drivers from configuration.

Returns
true
false

◆ load_master()

virtual bool ros2_canopen::DeviceContainer::load_master ( )
virtual

Loads master from configuration.

Returns
true
false

◆ load_manager()

virtual bool ros2_canopen::DeviceContainer::load_manager ( )
virtual

Loads the device manager.

Returns
true
false

◆ load_component()

virtual bool ros2_canopen::DeviceContainer::load_component ( std::string &  package_name,
std::string &  driver_name,
uint16_t  node_id,
std::string &  node_name,
std::vector< rclcpp::Parameter > &  params 
)
virtual

Load a component.

Parameters
[in]package_nameName of the package
[in]driver_nameName of the driver class to load
[in]node_idCANopen node id of the target device
[in]node_nameNode name of the ROS node
Returns
true
false

◆ shutdown()

virtual void ros2_canopen::DeviceContainer::shutdown ( )
inlinevirtual

Shutdown all devices.

This function will shutdown all devices that were created. The function calls the shutdown function of each created device.

◆ on_list_nodes()

virtual void ros2_canopen::DeviceContainer::on_list_nodes ( const std::shared_ptr< rmw_request_id_t >  request_header,
const std::shared_ptr< ListNodes::Request >  request,
std::shared_ptr< ListNodes::Response >  response 
)
overridevirtual

Callback for the listing service.

Parameters
request_header
request
response

◆ get_registered_drivers()

virtual std::map<uint16_t, std::shared_ptr<CanopenDriverInterface> > ros2_canopen::DeviceContainer::get_registered_drivers ( )
inlinevirtual

Get the registered drivers object.

This function will return a map of all driver objects that were created. The returned map can be queried by node id.

Returns
std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>>

◆ count_drivers()

virtual size_t ros2_canopen::DeviceContainer::count_drivers ( )
inlinevirtual

Get the number of registered drivers.

Returns
size_t

◆ get_ids_of_drivers_with_type()

std::vector<uint16_t> ros2_canopen::DeviceContainer::get_ids_of_drivers_with_type ( std::string  type)
inline

Get node ids of all drivers with type.

This function gets the ids of all drivers that have the passed in type. The type must be the fully qualified class name of the driver as string.

Parameters
[in]type
Returns
std::vector<uint16_t>

◆ get_driver_type()

std::string ros2_canopen::DeviceContainer::get_driver_type ( uint16_t  id)
inline

Get the type of driver by node id.

This function will return the type of the driver that is registered for the passed node ids.

Parameters
[in]id
Returns
std::string

◆ set_executor()

void ros2_canopen::DeviceContainer::set_executor ( const std::weak_ptr< rclcpp::Executor >  executor)
protected

Set the ROS executor object.

Parameters
[in]executorPointer to the Executor

◆ init_driver()

bool ros2_canopen::DeviceContainer::init_driver ( uint16_t  node_id)
protected

Initialises a driver.

This function needs to be called before a driver can be added to the CANopen Master Event Loop. It sets the master and executor, the driver will be added to.

Parameters
node_idCANopen node id of the target device
Returns
true
false

◆ on_init_driver()

void ros2_canopen::DeviceContainer::on_init_driver ( const canopen_interfaces::srv::CONode::Request::SharedPtr  request,
canopen_interfaces::srv::CONode::Response::SharedPtr  response 
)
inlineprotected

Callback for init driver service.

Parameters
request
response

◆ list_components()

std::map<uint16_t, std::string> ros2_canopen::DeviceContainer::list_components ( )
protected

Returns a list of components.

Returns
std::map<uint16_t, std::string>

◆ add_node_to_executor()

virtual void ros2_canopen::DeviceContainer::add_node_to_executor ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_interface)
inlineprotectedvirtual

Add node to executor.

Parameters
[in]node_interfaceNodeBaseInterface of the node that should be added to the executor.

Member Data Documentation

◆ registered_drivers_

std::map<uint16_t, std::shared_ptr<CanopenDriverInterface> > ros2_canopen::DeviceContainer::registered_drivers_
protected

Map of drivers registered in busconfiguration. Name is key.

◆ can_master_

std::shared_ptr<ros2_canopen::CanopenMasterInterface> ros2_canopen::DeviceContainer::can_master_
protected

Pointer to can master instance.

◆ can_master_id_

uint16_t ros2_canopen::DeviceContainer::can_master_id_
protected

◆ lifecycle_manager_

std::unique_ptr<ros2_canopen::LifecycleManager> ros2_canopen::DeviceContainer::lifecycle_manager_
protected

◆ config_

std::shared_ptr<ros2_canopen::ConfigurationManager> ros2_canopen::DeviceContainer::config_
protected

Pointer to configuration manager instance.

◆ dcf_txt_

std::string ros2_canopen::DeviceContainer::dcf_txt_
protected

Cached value of .dcf file parameter.

◆ bus_config_

std::string ros2_canopen::DeviceContainer::bus_config_
protected

Cached value of bus.yml file parameter.

◆ dcf_bin_

std::string ros2_canopen::DeviceContainer::dcf_bin_
protected

Cached value of .bin file parameter.

◆ can_interface_name_

std::string ros2_canopen::DeviceContainer::can_interface_name_
protected

Cached value of can interface name.

◆ lifecycle_operation_

bool ros2_canopen::DeviceContainer::lifecycle_operation_
protected

◆ executor_

std::weak_ptr<rclcpp::Executor> ros2_canopen::DeviceContainer::executor_
protected

Pointer to ros executor instance.

◆ init_driver_service_

rclcpp::Service<canopen_interfaces::srv::CONode>::SharedPtr ros2_canopen::DeviceContainer::init_driver_service_
protected

Service object for init_driver service.

◆ client_cbg_

rclcpp::CallbackGroup::SharedPtr ros2_canopen::DeviceContainer::client_cbg_
protected

Callback group for services.


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