7 #include <franka_msgs/ErrorRecoveryAction.h> 54 std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>
~FrankaCombinedHW() override=default
bool controllerNeedsReset()
Checks whether the controller needs to be reset.
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
The init function is called to initialize the CombinedFrankaHW from a non-realtime thread...
FrankaCombinedHW()
Creates an instance of CombinedFrankaHW.
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > combined_recovery_action_server_
void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the robot HW.