Template Class NodeCanopenMaster
Defined in File node_canopen_master.hpp
Inheritance Relationships
Base Type
public ros2_canopen::node_interfaces::NodeCanopenMasterInterface
(Class NodeCanopenMasterInterface)
Class Documentation
-
template<class NODETYPE>
class NodeCanopenMaster : public ros2_canopen::node_interfaces::NodeCanopenMasterInterface Node Canopen Master.
This class implements the NodeCanopenMasterInterface. It provides core functionality and logic for CanopenMaster, indepentently of the ROS node type. Currently rclcpp::Node and rclcpp_lifecycle::LifecycleNode and derived classes are supported. Other node types will lead to compile time error.
- Template Parameters:
NODETYPE –
Public Functions
-
inline virtual void init() override
Initialise Master.
-
inline virtual void init(bool called_from_base)
-
inline virtual void configure() override
Configure the driver.
This function should contain the configuration related things, such as reading parameter data or configuration data from files.
-
inline virtual void configure(bool called_from_base)
-
inline virtual void activate() override
Activate the driver.
This function should activate the driver, consequently it needs to start all timers and threads necessary for the operation of the driver.
-
inline virtual void activate(bool called_from_base)
Activate hook for derived classes.
This function should create a Master using exec_, timer_, master_dcf_, master_bin_ and node_id_ members and store it in master_. It should also create a thread and run the master’s event loop.
- Parameters:
called_from_base –
-
inline virtual void deactivate() override
Deactivate the driver.
This function should deactivate the driver, consequently it needs to stop all timers and threads that are related to the operation of the diver.
-
inline virtual void deactivate(bool called_from_base)
Deactivate hook for derived classes.
This function should wait to join the thread created in the activate function.
- Parameters:
called_from_base –
-
inline virtual void cleanup() override
Cleanup the driver.
This function needs to clean the internal state of the driver. This means all data should be deleted.
-
inline virtual void cleanup(bool called_from_base)
-
inline virtual void shutdown() override
Shutdown the driver.
This function should shutdown the driver.
-
inline virtual void shutdown(bool called_from_base)
-
inline virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master()
Get the master object.
- Returns:
std::shared_ptr<lely::canopen::AsyncMaster>
-
inline virtual std::shared_ptr<lely::ev::Executor> get_executor()
Get the executor object.
- Returns:
std::shared_ptr<lely::canopen::Executor>
Protected Attributes
-
std::atomic<bool> initialised_
-
std::atomic<bool> configured_
-
std::atomic<bool> activated_
-
std::atomic<bool> master_set_
-
std::shared_ptr<lely::canopen::AsyncMaster> master_
-
std::shared_ptr<lely::ev::Executor> exec_
-
std::unique_ptr<lely::io::IoGuard> io_guard_
-
std::unique_ptr<lely::io::Context> ctx_
-
std::unique_ptr<lely::io::Poll> poll_
-
std::unique_ptr<lely::ev::Loop> loop_
-
std::unique_ptr<lely::io::Timer> timer_
-
std::unique_ptr<lely::io::CanController> ctrl_
-
std::unique_ptr<lely::io::CanChannel> chan_
-
std::unique_ptr<lely::io::SignalSet> sigset_
-
rclcpp::CallbackGroup::SharedPtr client_cbg_
-
rclcpp::CallbackGroup::SharedPtr timer_cbg_
-
YAML::Node config_
-
uint8_t node_id_
-
std::chrono::milliseconds non_transmit_timeout_
-
std::string container_name_
-
std::string master_dcf_
-
std::string master_bin_
-
std::string can_interface_name_
-
std::thread spinner_