17 #include <franka/control_types.h>
18 #include <franka/rate_limiting.h>
19 #include <franka/robot.h>
25 std::ostream&
operator<<(std::ostream& ostream, franka::ControllerMode mode) {
26 if (mode == franka::ControllerMode::kJointImpedance) {
27 ostream <<
"joint_impedance";
28 }
else if (mode == franka::ControllerMode::kCartesianImpedance) {
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!");
234 run_function_(*
robot_, [
this, ros_callback, &last_time](
const franka::RobotState& robot_state,
235 franka::Duration time_step) {
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);
419 franka::CartesianVelocities& velocity_cartesian_command) {
422 velocity_cartesian_command.elbow);
436 const bool limit_rate,
437 const double cutoff_frequency,
438 const franka::ControllerMode internal_controller) {
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);
562 franka::ControllerMode controller_mode;
563 if (internal_controller ==
"joint_impedance") {
564 controller_mode = franka::ControllerMode::kJointImpedance;
565 }
else if (internal_controller ==
"cartesian_impedance") {
566 controller_mode = franka::ControllerMode::kCartesianImpedance;
568 ROS_WARN(
"Invalid internal_controller parameter provided, falling back to joint impedance");
569 controller_mode = franka::ControllerMode::kJointImpedance;
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());