Class MultiPumaNode
Defined in File multi_puma_node.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class MultiPumaNode : public rclcpp::Node
Public Functions
-
MultiPumaNode(const std::string node_name)
Receives desired motor speeds in sensor_msgs::JointState format and sends commands to each motor over CAN.
-
bool getFeedback()
Checks if feedback fields have been received from each motor driver. If feedback is avaiable, creates the feedback message and returns true. Otherwise, returns false.
-
bool getStatus()
Checks if status fields have been received from each motor driver. If status data is available, creates the status message and returns true. Otherwise, returns false.
-
void publishFeedback()
If feedback message was created, publishes feedback message.
-
void publishStatus()
If status message was created, publishes status message.
-
bool areAllActive()
Checks that all motor drivers have been configured and are active.
-
bool connectIfNotConnected()
Checks if socket connection is active. If not, attempts to establish a connection.
-
void run()
Main control loop that checks and maintains the socket gateway, resets and reconfigures drivers that have disconnected, verifies parameters are set appropriately, receives motor data, and publishes the feedback and status messages.
-
MultiPumaNode(const std::string node_name)