Go to the documentation of this file.
7 #include <franka_msgs/ErrorRecoveryAction.h>
70 std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>
void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the robot HW.
bool disconnect()
Tries to disconnect on all hardware classes that are of type FrankaCombinableHW.
ros::ServiceServer connect_server_
FrankaCombinedHW()
Creates an instance of CombinedFrankaHW.
ros::ServiceServer disconnect_server_
bool controllerNeedsReset()
Checks whether the controller needs to be reset.
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > combined_recovery_action_server_
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.
void connect()
Calls connect on all hardware classes that are of type FrankaCombinableHW.
bool hasError()
Checks whether the robots are in error or reflex mode.
~FrankaCombinedHW() override=default
franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21