Class DeviceContainer
Defined in File device_container.hpp
Inheritance Relationships
Base Type
public rclcpp_components::ComponentManager
Class Documentation
-
class DeviceContainer : public rclcpp_components::ComponentManager
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.
Public Functions
-
inline 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.
- Parameters:
executor – [in] The executor to add loaded master and devices to.
node_name – [in] The name of the node
node_options – [in] Passed to the device_container node
-
void 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
- Returns:
false
-
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.
Same as init() only that ros parameters are not used.
- Parameters:
can_interface_name –
master_config –
bus_config –
master_bin –
-
virtual void configure()
-
virtual bool load_drivers()
Loads drivers from configuration.
- Returns:
true
- Returns:
false
-
virtual bool load_master()
Loads master from configuration.
- Returns:
true
- Returns:
false
-
virtual bool load_manager()
Loads the device manager.
- Returns:
true
- Returns:
false
-
virtual bool load_component(std::string &package_name, std::string &driver_name, uint16_t node_id, std::string &node_name, std::vector<rclcpp::Parameter> ¶ms)
Load a component.
- Parameters:
package_name – [in] Name of the package
driver_name – [in] Name of the driver class to load
node_id – [in] CANopen node id of the target device
node_name – [in] Node name of the ROS node
- Returns:
true
- Returns:
false
-
inline virtual void shutdown()
Shutdown all devices.
This function will shutdown all devices that were created. The function calls the shutdown function of each created device.
Callback for the listing service.
- Parameters:
request_header –
request –
response –
-
inline virtual std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>> get_registered_drivers()
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>>
-
inline virtual size_t count_drivers()
Get the number of registered drivers.
- Returns:
size_t
-
inline std::vector<uint16_t> get_ids_of_drivers_with_type(std::string type)
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:
type – [in]
- Returns:
std::vector<uint16_t>
-
inline std::string get_driver_type(uint16_t id)
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:
id – [in]
- Returns:
std::string
Protected Functions
-
void set_executor(const std::weak_ptr<rclcpp::Executor> executor)
Set the ROS executor object.
- Parameters:
executor – [in] Pointer to the Executor
-
bool init_driver(uint16_t node_id)
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_id – CANopen node id of the target device
- Returns:
true
- Returns:
false
Callback for init driver service.
- Parameters:
request –
response –
-
std::map<uint16_t, std::string> list_components()
Returns a list of components.
- Returns:
std::map<uint16_t, std::string>
Add node to executor.
- Parameters:
node_interface – [in] NodeBaseInterface of the node that should be added to the executor.
Protected Attributes
-
std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>> registered_drivers_
Map of drivers registered in busconfiguration. Name is key.
-
std::shared_ptr<ros2_canopen::CanopenMasterInterface> can_master_
Pointer to can master instance.
-
uint16_t can_master_id_
-
std::unique_ptr<ros2_canopen::LifecycleManager> lifecycle_manager_
-
std::shared_ptr<ros2_canopen::ConfigurationManager> config_
Pointer to configuration manager instance.
-
std::string dcf_txt_
Cached value of .dcf file parameter.
-
std::string bus_config_
Cached value of bus.yml file parameter.
-
std::string dcf_bin_
Cached value of .bin file parameter.
-
std::string can_interface_name_
Cached value of can interface name.
-
bool lifecycle_operation_
-
std::weak_ptr<rclcpp::Executor> executor_
Pointer to ros executor instance.
-
rclcpp::Service<canopen_interfaces::srv::CONode>::SharedPtr init_driver_service_
Service object for init_driver service.
-
rclcpp::CallbackGroup::SharedPtr client_cbg_
Callback group for services.
-
inline 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())