EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
LifecycleNodeManager Class Reference
Inheritance diagram for LifecycleNodeManager:
[legend]
Collaboration diagram for LifecycleNodeManager:
[legend]

Public Member Functions

 LifecycleNodeManager (const std::string &node_name)
 
void HandleGuiNodeCallbacks (const ecat_msgs::msg::GuiButtonData::SharedPtr msg)
 
void HandleLifecycleNodeCallbacks (const ecat_msgs::msg::DataReceived::SharedPtr msg)
 
void init ()
 
unsigned int get_state ()
 Requests the current state of the node. More...
 
bool change_state (std::uint8_t transition)
 Invokes a transition. More...
 

Public Attributes

rclcpp::Subscription< sensor_msgs::msg::Joy >::SharedPtr joystick_subscriber_
 
rclcpp::Subscription< ecat_msgs::msg::GuiButtonData >::SharedPtr gui_button_subscriber_
 
rclcpp::Subscription< ecat_msgs::msg::DataReceived >::SharedPtr lifecycle_node_subscriber_
 
ecat_msgs::msg::DataReceived lifecycle_node_data_
 
Controller controller_
 

Private Attributes

std::shared_ptr< rclcpp::Client< lifecycle_msgs::srv::GetState > > client_get_state_
 
std::shared_ptr< rclcpp::Client< lifecycle_msgs::srv::ChangeState > > client_change_state_
 

Constructor & Destructor Documentation

◆ LifecycleNodeManager()

LifecycleNodeManager::LifecycleNodeManager ( const std::string &  node_name)
inlineexplicit

Subscribtion for control node. Subscribtion for slave feedback values acquired from connected slaves.

Member Function Documentation

◆ change_state()

bool LifecycleNodeManager::change_state ( std::uint8_t  transition)
inline

Invokes a transition.

We send a Service request and indicate that we want to invoke transition with the id "transition". By default, these transitions are

  • configure
  • activate
  • cleanup
  • shutdown
    Parameters
    transitionid specifying which transition to invoke
    time_outDuration in seconds specifying how long we wait for a response before returning unknown state

◆ get_state()

unsigned int LifecycleNodeManager::get_state ( )
inline

Requests the current state of the node.

In this function, we send a service request asking for the current state of the node ecat_node. If it does return within the given time_out, we return the current state of the node, if not, we return an unknown state.

Parameters
time_outDuration in seconds specifying how long we wait for a response before returning unknown state

◆ HandleGuiNodeCallbacks()

void LifecycleNodeManager::HandleGuiNodeCallbacks ( const ecat_msgs::msg::GuiButtonData::SharedPtr  msg)
inline

◆ HandleLifecycleNodeCallbacks()

void LifecycleNodeManager::HandleLifecycleNodeCallbacks ( const ecat_msgs::msg::DataReceived::SharedPtr  msg)
inline

◆ init()

void LifecycleNodeManager::init ( )
inline

Member Data Documentation

◆ client_change_state_

std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::ChangeState> > LifecycleNodeManager::client_change_state_
private

◆ client_get_state_

std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetState> > LifecycleNodeManager::client_get_state_
private

◆ controller_

Controller LifecycleNodeManager::controller_

◆ gui_button_subscriber_

rclcpp::Subscription<ecat_msgs::msg::GuiButtonData>::SharedPtr LifecycleNodeManager::gui_button_subscriber_

◆ joystick_subscriber_

rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr LifecycleNodeManager::joystick_subscriber_

◆ lifecycle_node_data_

ecat_msgs::msg::DataReceived LifecycleNodeManager::lifecycle_node_data_

◆ lifecycle_node_subscriber_

rclcpp::Subscription<ecat_msgs::msg::DataReceived>::SharedPtr LifecycleNodeManager::lifecycle_node_subscriber_

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