27 ostream <<
"joint_impedance";
29 ostream <<
"cartesian_impedance";
31 ostream <<
"<unknown>";
36 std::string toStringWithPrecision(
const double value,
const size_t precision = 6) {
37 std::ostringstream out;
38 out.precision(precision);
39 out << std::fixed << value;
46 : position_joint_command_ros_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}),
47 position_joint_command_libfranka_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}),
48 velocity_joint_command_ros_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}),
49 velocity_joint_command_libfranka_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}),
50 effort_joint_command_ros_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}),
51 effort_joint_command_libfranka_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}),
52 pose_cartesian_command_ros_(
53 {1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0}),
54 pose_cartesian_command_libfranka_(
55 {1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0}),
56 velocity_cartesian_command_ros_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0}),
57 velocity_cartesian_command_libfranka_({0.0, 0.0, 0.0, 0.0, 0.0, 0.0}) {}
61 ROS_ERROR(
"FrankaHW: Cannot be initialized twice.");
66 ROS_ERROR(
"FrankaHW: Failed to parse all required parameters.");
71 }
catch (
const std::runtime_error& error) {
72 ROS_ERROR(
"FrankaHW: Failed to initialize libfranka robot. %s", error.what());
83 std::vector<std::string> joint_names_vector;
84 if (!robot_hw_nh.
getParam(
"joint_names", joint_names_vector) || joint_names_vector.size() != 7) {
85 ROS_ERROR(
"Invalid or no joint_names parameters provided");
88 std::copy(joint_names_vector.cbegin(), joint_names_vector.cend(),
joint_names_.begin());
92 ROS_ERROR(
"Invalid or no rate_limiting parameter provided");
96 double cutoff_frequency;
97 if (!robot_hw_nh.
getParamCached(
"cutoff_frequency", cutoff_frequency)) {
98 ROS_ERROR(
"Invalid or no cutoff_frequency parameter provided");
102 std::string internal_controller;
103 if (!robot_hw_nh.
getParam(
"internal_controller", internal_controller)) {
104 ROS_ERROR(
"No internal_controller parameter provided");
109 ROS_ERROR(
"Invalid or no arm_id parameter provided");
114 ROS_ERROR(
"Could not initialize URDF model from robot_description");
119 ROS_ERROR(
"Invalid or no robot_ip parameter provided");
125 "No parameter joint_limit_warning_threshold is found, using default " 130 std::string realtime_config_param = robot_hw_nh.
param(
"realtime_config", std::string(
"enforce"));
131 if (realtime_config_param ==
"enforce") {
133 }
else if (realtime_config_param ==
"ignore") {
136 ROS_ERROR(
"Invalid realtime_config parameter provided. Valid values are 'enforce', 'ignore'.");
141 std::vector<double> thresholds =
143 {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
144 std::copy(thresholds.begin(), thresholds.end(),
147 {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
148 std::copy(thresholds.begin(), thresholds.end(),
151 {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
152 std::copy(thresholds.begin(), thresholds.end(),
155 {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
156 std::copy(thresholds.begin(), thresholds.end(),
158 thresholds.resize(6);
160 {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
161 std::copy(thresholds.begin(), thresholds.end(),
164 {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
165 std::copy(thresholds.begin(), thresholds.end(),
168 {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
169 std::copy(thresholds.begin(), thresholds.end(),
172 {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
173 std::copy(thresholds.begin(), thresholds.end(),
196 ROS_ERROR(
"FrankaHW: Rejected attempt to disconnect while controller is still running!");
224 ROS_ERROR(
"FrankaHW: Call to control before initialization!");
236 if (last_time != robot_state.
time) {
237 last_time = robot_state.time;
239 return ros_callback(ros::Time::now(), ros::Duration(time_step.toSec()));
246 if (period.
toSec() > 0.0) {
269 const std::list<hardware_interface::ControllerInfo>& ) {
278 const std::list<hardware_interface::ControllerInfo>& stop_list) {
282 ROS_ERROR(
"FrankaHW: Unknown interface claimed for starting!");
291 ROS_ERROR(
"FrankaHW: Unknown interface claimed for stopping!");
297 requested_control_mode &= ~stop_control_mode;
298 requested_control_mode |= start_control_mode;
307 << requested_control_mode <<
" with parameters " 335 std::string joint_limits_warning;
339 auto urdf_joint =
urdf_model_.getJoint(k_joint_name);
344 double joint_position = joint_handle.getPosition();
345 double dist = fmin(fabs(joint_position - joint_lower), fabs(joint_position - joint_upper));
347 joint_limits_warning +=
348 "\n\t" + k_joint_name +
": " + toStringWithPrecision(dist * 180 / M_PI) +
349 " degrees to joint limits (limits: [" + toStringWithPrecision(joint_lower) +
", " +
350 toStringWithPrecision(joint_upper) +
"]" +
351 " q: " + toStringWithPrecision(joint_position) +
") ";
355 << k_joint_name <<
" for joint limit interfaces");
364 if (!joint_limits_warning.empty()) {
372 ?
"FrankaHW: Attempt to access robot before initialization!" 373 :
"FrankaHW: Attempt to access disconnected robot!";
374 throw std::logic_error(error_message);
398 &robot_state.
dq[i], &robot_state.
tau_J[i]);
413 pose_cartesian_command.
elbow);
422 velocity_cartesian_command.
elbow);
436 const bool limit_rate,
437 const double cutoff_frequency,
439 using std::placeholders::_1;
440 using std::placeholders::_2;
441 using Callback = std::function<bool(const franka::RobotState&, franka::Duration)>;
443 switch (requested_control_mode) {
448 robot.
control(std::bind(&FrankaHW::controlCallback<franka::Torques>,
this,
450 limit_rate, cutoff_frequency);
455 robot.
control(std::bind(&FrankaHW::controlCallback<franka::JointPositions>,
this,
457 internal_controller, limit_rate, cutoff_frequency);
462 robot.
control(std::bind(&FrankaHW::controlCallback<franka::JointVelocities>,
this,
464 internal_controller, limit_rate, cutoff_frequency);
469 robot.
control(std::bind(&FrankaHW::controlCallback<franka::CartesianPose>,
this,
471 internal_controller, limit_rate, cutoff_frequency);
477 std::bind(&FrankaHW::controlCallback<franka::CartesianVelocities>,
this,
479 internal_controller, limit_rate, cutoff_frequency);
484 robot.
control(std::bind(&FrankaHW::controlCallback<franka::Torques>,
this,
486 std::bind(&FrankaHW::controlCallback<franka::JointPositions>,
this,
488 limit_rate, cutoff_frequency);
493 robot.
control(std::bind(&FrankaHW::controlCallback<franka::Torques>,
this,
495 std::bind(&FrankaHW::controlCallback<franka::JointVelocities>,
this,
497 limit_rate, cutoff_frequency);
502 robot.
control(std::bind(&FrankaHW::controlCallback<franka::Torques>,
this,
504 std::bind(&FrankaHW::controlCallback<franka::CartesianPose>,
this,
506 limit_rate, cutoff_frequency);
512 std::bind(&FrankaHW::controlCallback<franka::Torques>,
this,
514 std::bind(&FrankaHW::controlCallback<franka::CartesianVelocities>,
this,
516 limit_rate, cutoff_frequency);
520 ROS_WARN(
"FrankaHW: No valid control mode selected; cannot switch controllers.");
534 setupLimitInterface<joint_limits_interface::PositionJointSoftLimitsHandle>(
536 setupLimitInterface<joint_limits_interface::VelocityJointSoftLimitsHandle>(
538 setupLimitInterface<joint_limits_interface::EffortJointSoftLimitsHandle>(
548 model_ = std::make_unique<franka_hw::Model>(
robot_->loadModel());
556 return rate_limiting;
560 std::string internal_controller;
561 robot_hw_nh.
getParamCached(
"internal_controller", internal_controller);
563 if (internal_controller ==
"joint_impedance") {
565 }
else if (internal_controller ==
"cartesian_impedance") {
568 ROS_WARN(
"Invalid internal_controller parameter provided, falling back to joint impedance");
571 return controller_mode;
575 double cutoff_frequency;
577 return cutoff_frequency;
603 const std::vector<double>& defaults) {
604 std::vector<double> thresholds;
605 if (!robot_hw_nh.
getParam(
"collision_config/" + name, thresholds) ||
606 thresholds.size() != defaults.size()) {
608 for (
const double& threshold : defaults) {
609 message += std::to_string(threshold);
612 ROS_INFO(
"No parameter %s found, using default values: %s", name.c_str(), message.c_str());
void registerInterface(T *iface)
static bool arrayHasNaN(const std::array< double, size > &array)
Checks whether an array of doubles contains NaN values.
FrankaStateInterface franka_state_interface_
virtual std::array< double, 7 > getJointPositionCommand() const noexcept
Gets the current joint position command.
virtual std::mutex & robotMutex()
Getter for the mutex protecting access to the libfranka::robot class.
virtual void enforceLimits(const ros::Duration &period)
Enforces limits on position, velocity, and torque level.
virtual void setupFrankaCartesianPoseInterface(franka::CartesianPose &pose_cartesian_command)
Configures and registers the command interface for Cartesian poses in ros_control.
std::array< double, 7 > q
virtual void setupFrankaModelInterface(franka::RobotState &robot_state)
Configures and registers the model interface offering kinematics and dynamics in ros_control.
virtual void connect()
Create a libfranka robot, connecting the hardware class to the master controller. ...
virtual void reset()
Resets the limit interfaces.
std::ostream & operator<<(std::ostream &ostream, ControlMode mode)
std::array< double, 7 > lower_torque_thresholds_nominal
std::array< double, 7 > dq
virtual bool controllerActive() const noexcept
Indicates whether there is an active controller.
std::array< double, 16 > O_T_EE
franka::CartesianVelocities velocity_cartesian_command_libfranka_
virtual void setupFrankaCartesianVelocityInterface(franka::CartesianVelocities &velocity_cartesian_command)
Configures and registers the command interface for Cartesian velocities in ros_control.
franka::CartesianVelocities velocity_cartesian_command_ros_
FrankaPoseCartesianInterface franka_pose_cartesian_interface_
virtual void update(const franka::RobotState &robot_state)
Updates the controller interfaces from the given robot state.
franka::Torques effort_joint_command_ros_
std::array< double, 7 > lower_torque_thresholds_acceleration
franka::JointVelocities velocity_joint_command_libfranka_
Handle to read the complete state of a robot.
FrankaVelocityCartesianInterface franka_velocity_cartesian_interface_
franka::JointVelocities velocity_joint_command_ros_
CollisionConfig collision_config_
virtual 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...
virtual void checkJointLimits()
Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint...
URDF_EXPORT bool initParamWithNodeHandle(const std::string ¶m, const ros::NodeHandle &nh=ros::NodeHandle())
bool getArmClaimedMap(ResourceWithClaimsMap &resource_map, ArmClaimedMap &arm_claim_map)
std::map< std::string, std::vector< std::vector< std::string > >> ResourceWithClaimsMap
virtual bool setRunFunction(const ControlMode &requested_control_mode, bool limit_rate, double cutoff_frequency, franka::ControllerMode internal_controller)
Configures the run function which is used as libfranka control callback based on the requested contro...
void control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
franka::Torques effort_joint_command_libfranka_
bool hasConflictingJointAndCartesianClaim(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
franka::JointPositions position_joint_command_libfranka_
ControlMode getControlMode(const std::string &arm_id, ArmClaimedMap &arm_claim_map)
void enforceLimits(const ros::Duration &period)
std::map< std::string, ResourceClaims > ArmClaimedMap
FrankaHW()
Default constructor.
franka::RobotState robot_state_ros_
std::mutex ros_state_mutex_
virtual void write(const ros::Time &time, const ros::Duration &period) override
Writes data to the franka robot.
std::array< double, 6 > lower_force_thresholds_acceleration
franka::JointPositions position_joint_command_ros_
std::array< double, 7 > q
virtual void initRobot()
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
virtual bool connected()
Checks whether the hardware class is connected to a robot.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const char * what() const noexcept override
std::mutex libfranka_cmd_mutex_
std::unique_ptr< franka::Robot > robot_
std::array< double, 7 > upper_torque_thresholds_acceleration
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, JointLimits &limits)
ControlMode current_control_mode_
std::array< double, 6 > upper_force_thresholds_nominal
franka::RobotState robot_state_libfranka_
#define ROS_WARN_THROTTLE(period,...)
std::mutex ros_cmd_mutex_
hardware_interface::EffortJointInterface effort_joint_interface_
bool getParam(const std::string &key, std::string &s) const
Handle to read and command a Cartesian velocity.
virtual bool disconnect()
Tries to disconnect the hardware class from the robot, freeing it for e.g.
std::unique_ptr< franka_hw::ModelBase > model_
std::array< std::string, 7 > joint_names_
franka::RealtimeConfig realtime_config_
virtual std::array< double, 7 > getJointEffortCommand() const noexcept
Gets the current joint torque command.
std::array< double, 7 > dq
std::atomic_bool controller_active_
std::array< double, 2 > elbow
std::function< double()> get_cutoff_frequency_
virtual bool initParameters(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
Reads the parameterization of the hardware class from the ROS parameter server (e.g.
std::function< franka::ControllerMode()> get_internal_controller_
virtual void setupParameterCallbacks(ros::NodeHandle &robot_hw_nh)
Initializes the callbacks for on-the-fly reading the parameters for rate limiting, internal controllers and cutoff frequency.
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...
virtual void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the franka robot.
void registerHandle(const JointStateHandle &handle)
Handle to read and command a Cartesian pose.
hardware_interface::PositionJointInterface position_joint_interface_
joint_limits_interface::PositionJointSoftLimitsInterface position_joint_limit_interface_
bool getParamCached(const std::string &key, std::string &s) const
JointStateHandle getHandle(const std::string &name)
virtual void setupJointStateInterface(franka::RobotState &robot_state)
Configures and registers the joint state interface in ros_control.
joint_limits_interface::VelocityJointSoftLimitsInterface velocity_joint_limit_interface_
#define ROS_INFO_STREAM(args)
virtual void control(const std::function< bool(const ros::Time &, const ros::Duration &)> &ros_callback)
Runs the currently active controller in a realtime loop.
double joint_limit_warning_threshold_
virtual bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
Prepares switching between controllers (not real-time capable).
std::array< double, 6 > O_dP_EE
FrankaModelInterface franka_model_interface_
std::array< double, 6 > lower_force_thresholds_nominal
static std::vector< double > getCollisionThresholds(const std::string &name, const ros::NodeHandle &robot_hw_nh, const std::vector< double > &defaults)
Parses a set of collision thresholds from the parameter server.
franka::CartesianPose pose_cartesian_command_ros_
bool partiallyClaimsArmJoints(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
hardware_interface::VelocityJointInterface velocity_joint_interface_
#define ROS_ERROR_STREAM_ONCE(args)
virtual void setupFrankaStateInterface(franka::RobotState &robot_state)
Configures and registers the state interface offering the full franka::RobotState in ros_control...
std::function< void(franka::Robot &, Callback)> run_function_
std::array< double, 7 > upper_torque_thresholds_nominal
hardware_interface::JointStateInterface joint_state_interface_
std::array< double, 6 > upper_force_thresholds_acceleration
std::array< double, 7 > tau_J
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
franka::CartesianPose pose_cartesian_command_libfranka_
#define ROS_ERROR_STREAM(args)
virtual franka::Robot & robot() const
Getter for the libfranka robot instance.
Handle to perform calculations using the dynamic model of a robot.
virtual std::array< double, 7 > getJointVelocityCommand() const noexcept
Gets the current joint velocity command.
std::array< double, 7 > tau_J
virtual void initROSInterfaces(ros::NodeHandle &robot_hw_nh)
Initializes the class in terms of ros_control interfaces.
std::function< bool(const franka::RobotState &, franka::Duration)> Callback
ResourceWithClaimsMap getResourceMap(const std::list< hardware_interface::ControllerInfo > &info)
bool hasConflictingMultiClaim(const ResourceWithClaimsMap &resource_map)
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &, const std::list< hardware_interface::ControllerInfo > &) override
Performs controller switching (real-time capable).
std::function< bool()> get_limit_rate_
std::mutex libfranka_state_mutex_
std::array< double, 2 > elbow
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.