EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
GUI::GuiNode Class Reference

This node will be responsible from all GUI interaction and visualization of feedback information acquired via EtherCAT communication. More...

#include <gui_node.hpp>

Inheritance diagram for GUI::GuiNode:
[legend]
Collaboration diagram for GUI::GuiNode:
[legend]

Public Member Functions

 GuiNode ()
 
virtual ~GuiNode ()
 

Public Attributes

ecat_msgs::msg::DataReceived slave_feedback_data_
 Received data structure to store all subscribed data. More...
 
ecat_msgs::msg::DataSent master_command_data_
 
ecat_msgs::msg::GuiButtonData ui_control_buttons_
 GUI button value to publish emergency button state. More...
 
std_msgs::msg::UInt16 safety_info_
 
Timing time_info_
 For time measurements. More...
 
uint8_t current_lifecycle_state = 0
 

Private Member Functions

void timer_callback ()
 Publishes gui button value in specified interval. More...
 
void HandleControllerCallbacks (const sensor_msgs::msg::Joy::SharedPtr msg)
 Function will be used for subscribtion callbacks from controller node for Controller topic. More...
 
void HandleMasterCommandCallbacks (const ecat_msgs::msg::DataSent::SharedPtr msg)
 Function will be used for subscribtion callbacks from EthercatLifecycle node for Master_Commands topic. More...
 
void HandleSlaveFeedbackCallbacks (const ecat_msgs::msg::DataReceived::SharedPtr msg)
 Function will be used for subscribtion callbacks from EthercatLifecycle node for Master_Commands topic. More...
 
void ResetContolButtonValues ()
 Resets control button values coming from control UI. More...
 
void HandleSafetyNodeCallback (const std_msgs::msg::UInt16::SharedPtr msg)
 

Private Attributes

rclcpp::Subscription< ecat_msgs::msg::DataReceived >::SharedPtr slave_feedback_
 
rclcpp::Subscription< ecat_msgs::msg::DataSent >::SharedPtr master_commands_
 Subscribed to commands that's being sent by ecat_master. More...
 
rclcpp::Subscription< sensor_msgs::msg::Joy >::SharedPtr controller_commands_
 
rclcpp::Subscription< std_msgs::msg::UInt16 >::SharedPtr safety_info_subscriber_
 
rclcpp::TimerBase::SharedPtr timer_
 Timer for timer callbacks, publishing will be done in certain interval. More...
 
rclcpp::Publisher< ecat_msgs::msg::GuiButtonData >::SharedPtr gui_publisher_
 Gui publisher, which contains clicked button information. More...
 

Detailed Description

This node will be responsible from all GUI interaction and visualization of feedback information acquired via EtherCAT communication.

Constructor & Destructor Documentation

◆ GuiNode()

GuiNode::GuiNode ( )

Subscribtion for control node.

Subscribtion for slave feedback values acquired from connected slaves.

Subscribtions for master commands to slaves.

Gui button value publisher

Timer callback set to 33HZ.

◆ ~GuiNode()

GuiNode::~GuiNode ( )
virtual

Member Function Documentation

◆ HandleControllerCallbacks()

void GuiNode::HandleControllerCallbacks ( const sensor_msgs::msg::Joy::SharedPtr  msg)
private

Function will be used for subscribtion callbacks from controller node for Controller topic.

Parameters
msgcontroller command structure published by controller node.

◆ HandleMasterCommandCallbacks()

void GuiNode::HandleMasterCommandCallbacks ( const ecat_msgs::msg::DataSent::SharedPtr  msg)
private

Function will be used for subscribtion callbacks from EthercatLifecycle node for Master_Commands topic.

Parameters
msgMaster commands structure published by EthercatLifecycle node

◆ HandleSafetyNodeCallback()

void GUI::GuiNode::HandleSafetyNodeCallback ( const std_msgs::msg::UInt16::SharedPtr  msg)
private

◆ HandleSlaveFeedbackCallbacks()

void GuiNode::HandleSlaveFeedbackCallbacks ( const ecat_msgs::msg::DataReceived::SharedPtr  msg)
private

Function will be used for subscribtion callbacks from EthercatLifecycle node for Master_Commands topic.

Parameters
msgSlave feedback structure published by EthercatLifecycle node

Servo Drive feedbacks

Costum slave feedbacks.

◆ ResetContolButtonValues()

void GuiNode::ResetContolButtonValues ( )
private

Resets control button values coming from control UI.

◆ timer_callback()

void GuiNode::timer_callback ( )
private

Publishes gui button value in specified interval.

Member Data Documentation

◆ controller_commands_

rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr GUI::GuiNode::controller_commands_
private

◆ current_lifecycle_state

uint8_t GUI::GuiNode::current_lifecycle_state = 0

◆ gui_publisher_

rclcpp::Publisher<ecat_msgs::msg::GuiButtonData>::SharedPtr GUI::GuiNode::gui_publisher_
private

Gui publisher, which contains clicked button information.

◆ master_command_data_

ecat_msgs::msg::DataSent GUI::GuiNode::master_command_data_

◆ master_commands_

rclcpp::Subscription<ecat_msgs::msg::DataSent>::SharedPtr GUI::GuiNode::master_commands_
private

Subscribed to commands that's being sent by ecat_master.

◆ safety_info_

std_msgs::msg::UInt16 GUI::GuiNode::safety_info_

◆ safety_info_subscriber_

rclcpp::Subscription<std_msgs::msg::UInt16>::SharedPtr GUI::GuiNode::safety_info_subscriber_
private

◆ slave_feedback_

rclcpp::Subscription<ecat_msgs::msg::DataReceived>::SharedPtr GUI::GuiNode::slave_feedback_
private

ROS2 subscriptions. Acquired feedback information from connected slaves

◆ slave_feedback_data_

ecat_msgs::msg::DataReceived GUI::GuiNode::slave_feedback_data_

Received data structure to store all subscribed data.

◆ time_info_

Timing GUI::GuiNode::time_info_

For time measurements.

◆ timer_

rclcpp::TimerBase::SharedPtr GUI::GuiNode::timer_
private

Timer for timer callbacks, publishing will be done in certain interval.

◆ ui_control_buttons_

ecat_msgs::msg::GuiButtonData GUI::GuiNode::ui_control_buttons_

GUI button value to publish emergency button state.


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