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

Public Member Functions

 SafetyNode (const std::string &node_name)
 
void PublishSafetyInfo ()
 
void SpinThread ()
 
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

std::thread spin_thread_
 
uint32_t state_ = lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN
 
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_
 
rclcpp::Publisher< std_msgs::msg::UInt16 >::SharedPtr safety_state_publisher_
 
ecat_msgs::msg::DataReceived lifecycle_node_data_
 
Controller controller_
 
std_msgs::msg::UInt16 safety_state_msg_
 
uint8_t button_request_ =0
 
rclcpp::TimerBase::SharedPtr timer_
 

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

◆ SafetyNode()

SafetyNode::SafetyNode ( 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 SafetyNode::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 SafetyNode::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 SafetyNode::HandleGuiNodeCallbacks ( const ecat_msgs::msg::GuiButtonData::SharedPtr  msg)
inline

◆ HandleLifecycleNodeCallbacks()

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

◆ init()

void SafetyNode::init ( )
inline

◆ PublishSafetyInfo()

void SafetyNode::PublishSafetyInfo ( )
inline

◆ SpinThread()

void SafetyNode::SpinThread ( )
inline

Member Data Documentation

◆ button_request_

uint8_t SafetyNode::button_request_ =0

◆ client_change_state_

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

◆ client_get_state_

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

◆ controller_

Controller SafetyNode::controller_

◆ gui_button_subscriber_

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

◆ joystick_subscriber_

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

◆ lifecycle_node_data_

ecat_msgs::msg::DataReceived SafetyNode::lifecycle_node_data_

◆ lifecycle_node_subscriber_

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

◆ safety_state_msg_

std_msgs::msg::UInt16 SafetyNode::safety_state_msg_

◆ safety_state_publisher_

rclcpp::Publisher<std_msgs::msg::UInt16>::SharedPtr SafetyNode::safety_state_publisher_

◆ spin_thread_

std::thread SafetyNode::spin_thread_

◆ state_

◆ timer_

rclcpp::TimerBase::SharedPtr SafetyNode::timer_

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