Go to the documentation of this file.
11 #include <std_msgs/Bool.h>
15 using namespace std::chrono_literals;
19 FrankaCombinableHW::FrankaCombinableHW() : has_error_(false), error_recovered_(false) {}
30 setupLimitInterface<joint_limits_interface::EffortJointSoftLimitsHandle>(
48 msg.data =
static_cast<int>(error);
59 ROS_DEBUG_THROTTLE(1,
"FrankaCombinableHW::%s::control_loop(): controller is not active.",
83 std::this_thread::sleep_for(1ms);
85 ROS_INFO(
"FrankaCombinableHW::%s::control_loop(): controller is active.",
arm_id_.c_str());
99 }
catch (
const franka::ControlException& e) {
111 "FrankaCombinableHW::setupServicesAndActionServers: Cannot create services without "
116 services_ = std::make_unique<ServiceContainer>();
121 std::make_unique<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>(
122 node_handle,
"error_recovery",
123 [&](
const franka_msgs::ErrorRecoveryGoalConstPtr&) {
127 robot_->automaticErrorRecovery();
135 }
catch (
const franka::Exception& ex) {
141 "Cannot recovery robot while disconnected.");
156 ROS_ERROR(
"FrankaHW: Rejected attempt to disconnect while controller is still running!");
169 auto empty_method = [](
const franka::RobotState&, franka::Duration) {
return true; };
174 const std::list<hardware_interface::ControllerInfo>& info)
const {
183 ROS_ERROR(
"FrankaCombinableHW: Unknown interface claimed. Conflict!");
189 ROS_ERROR_STREAM(
"FrankaCombinableHW: Invalid claim joint position or velocity interface."
190 <<
"Note: joint position and joint velocity interfaces are not supported"
191 <<
" in FrankaCombinableHW. Arm:" <<
arm_id_ <<
". Conflict!");
232 robot_->automaticErrorRecovery();
247 const bool limit_rate,
248 const double cutoff_frequency,
249 const franka::ControllerMode ) {
250 using Callback = std::function<bool(
const franka::RobotState&, franka::Duration)>;
259 robot.control(std::bind(&FrankaCombinableHW::libfrankaUpdateCallback<franka::Torques>,
this,
261 std::placeholders::_2),
262 limit_rate, cutoff_frequency);
267 ROS_ERROR(
"FrankaCombinableHW: No valid control mode selected; cannot set run function.");
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 setupJointCommandInterface(std::array< double, 7 > &command, franka::RobotState &state, bool use_q_d, T &interface)
Configures and registers a joint command interface for positions velocities or efforts in ros_control...
void publishErrorState(bool error)
void connect() override
Create a libfranka robot, connecting the hardware class to the master controller.
#define ROS_ERROR_STREAM(args)
bool getArmClaimedMap(ResourceWithClaimsMap &resource_map, ArmClaimedMap &arm_claim_map)
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.
std::string getArmID() const noexcept
Getter method for the arm_id which is used to distinguish between multiple instances of FrankaCombina...
virtual void setupFrankaModelInterface(franka::RobotState &robot_state)
Configures and registers the model interface offering kinematics and dynamics in ros_control.
virtual bool controllerActive() const noexcept
Indicates whether there is an active controller.
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.
std::mutex ros_cmd_mutex_
virtual void write(const ros::Time &time, const ros::Duration &period) override
Writes data to the franka robot.
virtual void setupJointStateInterface(franka::RobotState &robot_state)
Configures and registers the joint state interface in ros_control.
franka::Torques effort_joint_command_ros_
hardware_interface::EffortJointInterface effort_joint_interface_
void publish(const boost::shared_ptr< M > &message) const
bool partiallyClaimsArmJoints(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
Publisher advertise(AdvertiseOptions &ops)
virtual void initRobot()
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
std::function< void(franka::Robot &, Callback)> run_function_
virtual void connect()
Create a libfranka robot, connecting the hardware class to the master controller.
void initRobot() override
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
franka::Torques effort_joint_command_libfranka_
virtual void checkJointLimits()
Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint...
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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_
void setupServices(franka::Robot &robot, std::mutex &robot_mutex, ros::NodeHandle &node_handle, ServiceContainer &services)
Sets up all services relevant for a libfranka robot inside a service container.
ros::Publisher has_error_pub_
franka::RobotState robot_state_ros_
virtual bool connected()
Checks whether the hardware class is connected to a robot.
std::unique_ptr< franka::Robot > robot_
std::map< std::string, ResourceClaims > ArmClaimedMap
bool disconnect() override
Tries to disconnect the hardware class from the robot, freeing it for e.g.
std::map< std::string, std::vector< std::vector< std::string > >> ResourceWithClaimsMap
virtual bool disconnect()
Tries to disconnect the hardware class from the robot, freeing it for e.g.
virtual void enforceLimits(const ros::Duration &period)
Enforces limits on position, velocity, and torque level.
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.
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
virtual void setupFrankaStateInterface(franka::RobotState &robot_state)
Configures and registers the state interface offering the full franka::RobotState in ros_control.
std::atomic_bool has_error_
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > recovery_action_server_
virtual void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the franka robot.
bool hasTrajectoryClaim(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
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.
ResourceWithClaimsMap getResourceMap(const std::list< hardware_interface::ControllerInfo > &info)
std::mutex ros_state_mutex_
std::function< bool(const franka::RobotState &, franka::Duration)> Callback
std::atomic_bool error_recovered_
bool hasConflictingMultiClaim(const ResourceWithClaimsMap &resource_map)
virtual franka::Robot & robot() const
Getter for the libfranka robot instance.
std::atomic_bool controller_active_
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_
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.
#define ROS_DEBUG_THROTTLE(period,...)
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