Go to the documentation of this file.
11 #include <franka/exception.h>
12 #include <franka/robot_state.h>
17 #include <franka_msgs/ErrorRecoveryAction.h>
95 bool checkForConflict(
const std::list<hardware_interface::ControllerInfo>& info)
const override;
119 std::string
getArmID()
const noexcept;
147 template <
typename T>
149 const franka::RobotState& robot_state,
150 franka::Duration time_step) {
152 std::string error_message =
"FrankaCombinableHW: Got NaN value in command!";
154 throw std::invalid_argument(error_message);
165 return franka::MotionFinished(current_cmd);
178 double cutoff_frequency,
179 franka::ControllerMode internal_controller)
override;
185 std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>
void read(const ros::Time &, const ros::Duration &) override
Reads data from the franka robot.
std::mutex libfranka_state_mutex_
std::unique_ptr< ServiceContainer > services_
void publishErrorState(bool error)
void connect() override
Create a libfranka robot, connecting the hardware class to the master controller.
This class wraps the functionality of libfranka for controlling Panda robots into the ros_control fra...
std::atomic_bool controller_needs_reset_
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
ROSLIB_DECL std::string command(const std::string &cmd)
std::string getArmID() const noexcept
Getter method for the arm_id which is used to distinguish between multiple instances of FrankaCombina...
bool controllerNeedsReset() const noexcept
Returns whether the controller needs to be reset e.g.
A hardware class for a Panda robot based on the ros_control framework.
T libfrankaUpdateCallback(const T &command, const franka::RobotState &robot_state, franka::Duration time_step)
void initRobot() override
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
virtual void checkJointLimits()
Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint...
bool setRunFunction(const ControlMode &requested_control_mode, bool limit_rate, double cutoff_frequency, franka::ControllerMode internal_controller) override
Configures the run function which is used as libfranka control callback based on the requested contro...
std::mutex libfranka_cmd_mutex_
ros::Publisher has_error_pub_
FrankaCombinableHW()
Creates an instance of FrankaCombinableHW.
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.
bool disconnect() override
Tries to disconnect the hardware class from the robot, freeing it for e.g.
franka::RobotState robot_state_libfranka_
ros::NodeHandle robot_hw_nh_
void initROSInterfaces(ros::NodeHandle &robot_hw_nh) override
Initializes the class in terms of ros_control interfaces.
bool hasError() const noexcept
Getter for the error flag of the class.
std::atomic_bool has_error_
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > recovery_action_server_
void setupServicesAndActionServers(ros::NodeHandle &node_handle)
std::unique_ptr< std::thread > control_loop_thread_
void write(const ros::Time &, const ros::Duration &period) override
Writes data to the franka robot.
std::atomic_bool error_recovered_
std::atomic_bool controller_active_
bool checkForConflict(const std::list< hardware_interface::ControllerInfo > &info) const override
Checks whether a requested controller can be run, based on the resources and interfaces it claims.
void resetError()
Recovers the libfranka robot, resets the error flag and publishes the error state.
void control(const std::function< bool(const ros::Time &, const ros::Duration &)> &ros_callback=[](const ros::Time &, const ros::Duration &) { return true;}) override
Runs the currently active controller in a realtime loop.
void triggerError()
Triggers a stop of the controlLoop.
franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21