franka_hw.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
3 #include <franka_hw/franka_hw.h>
5 
6 #include <array>
7 #include <cstdint>
8 #include <exception>
9 #include <functional>
10 #include <list>
11 #include <mutex>
12 #include <ostream>
13 #include <sstream>
14 #include <string>
15 #include <utility>
16 
17 #include <franka/control_types.h>
18 #include <franka/rate_limiting.h>
19 #include <franka/robot.h>
21 
22 namespace franka_hw {
23 
24 namespace {
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";
30  } else {
31  ostream << "<unknown>";
32  }
33  return ostream;
34 }
35 
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;
40  return out.str();
41 }
42 
43 } // anonymous namespace
44 
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}) {}
58 
59 bool FrankaHW::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) {
60  if (initialized_) {
61  ROS_ERROR("FrankaHW: Cannot be initialized twice.");
62  return false;
63  }
64 
65  if (!initParameters(root_nh, robot_hw_nh)) {
66  ROS_ERROR("FrankaHW: Failed to parse all required parameters.");
67  return false;
68  }
69  try {
70  initRobot();
71  } catch (const std::runtime_error& error) {
72  ROS_ERROR("FrankaHW: Failed to initialize libfranka robot. %s", error.what());
73  return false;
74  }
75  initROSInterfaces(robot_hw_nh);
76  setupParameterCallbacks(robot_hw_nh);
77 
78  initialized_ = true;
79  return true;
80 }
81 
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");
86  return false;
87  }
88  std::copy(joint_names_vector.cbegin(), joint_names_vector.cend(), joint_names_.begin());
89 
90  bool rate_limiting;
91  if (!robot_hw_nh.getParamCached("rate_limiting", rate_limiting)) {
92  ROS_ERROR("Invalid or no rate_limiting parameter provided");
93  return false;
94  }
95 
96  double cutoff_frequency;
97  if (!robot_hw_nh.getParamCached("cutoff_frequency", cutoff_frequency)) {
98  ROS_ERROR("Invalid or no cutoff_frequency parameter provided");
99  return false;
100  }
101 
102  std::string internal_controller;
103  if (!robot_hw_nh.getParam("internal_controller", internal_controller)) {
104  ROS_ERROR("No internal_controller parameter provided");
105  return false;
106  }
107 
108  if (!robot_hw_nh.getParam("arm_id", arm_id_)) {
109  ROS_ERROR("Invalid or no arm_id parameter provided");
110  return false;
111  }
112 
113  if (!urdf_model_.initParamWithNodeHandle("robot_description", root_nh)) {
114  ROS_ERROR("Could not initialize URDF model from robot_description");
115  return false;
116  }
117 
118  if (!robot_hw_nh.getParam("robot_ip", robot_ip_)) {
119  ROS_ERROR("Invalid or no robot_ip parameter provided");
120  return false;
121  }
122 
123  if (!robot_hw_nh.getParam("joint_limit_warning_threshold", joint_limit_warning_threshold_)) {
124  ROS_INFO(
125  "No parameter joint_limit_warning_threshold is found, using default "
126  "value %f",
128  }
129 
130  std::string realtime_config_param = robot_hw_nh.param("realtime_config", std::string("enforce"));
131  if (realtime_config_param == "enforce") {
132  realtime_config_ = franka::RealtimeConfig::kEnforce;
133  } else if (realtime_config_param == "ignore") {
134  realtime_config_ = franka::RealtimeConfig::kIgnore;
135  } else {
136  ROS_ERROR("Invalid realtime_config parameter provided. Valid values are 'enforce', 'ignore'.");
137  return false;
138  }
139 
140  // Get full collision behavior config from the parameter server.
141  std::vector<double> thresholds =
142  getCollisionThresholds("lower_torque_thresholds_acceleration", robot_hw_nh,
143  {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
144  std::copy(thresholds.begin(), thresholds.end(),
146  thresholds = getCollisionThresholds("upper_torque_thresholds_acceleration", robot_hw_nh,
147  {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
148  std::copy(thresholds.begin(), thresholds.end(),
150  thresholds = getCollisionThresholds("lower_torque_thresholds_nominal", robot_hw_nh,
151  {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
152  std::copy(thresholds.begin(), thresholds.end(),
154  thresholds = getCollisionThresholds("upper_torque_thresholds_nominal", robot_hw_nh,
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);
159  thresholds = getCollisionThresholds("lower_force_thresholds_acceleration", robot_hw_nh,
160  {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
161  std::copy(thresholds.begin(), thresholds.end(),
163  thresholds = getCollisionThresholds("upper_force_thresholds_acceleration", robot_hw_nh,
164  {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
165  std::copy(thresholds.begin(), thresholds.end(),
167  thresholds = getCollisionThresholds("lower_force_thresholds_nominal", robot_hw_nh,
168  {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
169  std::copy(thresholds.begin(), thresholds.end(),
171  thresholds = getCollisionThresholds("upper_force_thresholds_nominal", robot_hw_nh,
172  {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
173  std::copy(thresholds.begin(), thresholds.end(),
175 
176  return true;
177 }
178 
180  std::lock_guard<std::mutex> lock(robot_mutex_);
181  if (!robot_) {
182  robot_ = std::make_unique<franka::Robot>(robot_ip_, realtime_config_);
191  }
192 }
193 
195  if (controllerActive()) {
196  ROS_ERROR("FrankaHW: Rejected attempt to disconnect while controller is still running!");
197  return false;
198  }
199  std::lock_guard<std::mutex> lock(robot_mutex_);
200  robot_.reset();
201  return true;
202 }
203 
205  return robot_ != nullptr;
206 }
207 
208 void FrankaHW::update(const franka::RobotState& robot_state) {
209  std::lock_guard<std::mutex> ros_lock(ros_state_mutex_);
210  robot_state_ros_ = robot_state;
211 }
212 
213 bool FrankaHW::controllerActive() const noexcept {
214  return controller_active_;
215 }
216 
217 std::mutex& FrankaHW::robotMutex() {
218  return robot_mutex_;
219 }
220 
222  const std::function<bool(const ros::Time&, const ros::Duration&)>& ros_callback) {
223  if (!initialized_) {
224  ROS_ERROR("FrankaHW: Call to control before initialization!");
225  return;
226  }
227  if (!controller_active_) {
228  return;
229  }
230 
231  franka::Duration last_time = robot_state_ros_.time;
232 
233  std::lock_guard<std::mutex> lock(robot_mutex_);
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;
238 
239  return ros_callback(ros::Time::now(), ros::Duration(time_step.toSec()));
240  }
241  return true;
242  });
243 }
244 
246  if (period.toSec() > 0.0) {
250  }
251 }
252 
253 bool FrankaHW::checkForConflict(const std::list<hardware_interface::ControllerInfo>& info) const {
254  ResourceWithClaimsMap resource_map = getResourceMap(info);
255  if (hasConflictingMultiClaim(resource_map)) {
256  return true;
257  }
258  ArmClaimedMap arm_claim_map;
259  if (!getArmClaimedMap(resource_map, arm_claim_map)) {
260  ROS_ERROR_STREAM("FrankaHW: Unknown interface claimed. Conflict!");
261  return true;
262  }
263  return hasConflictingJointAndCartesianClaim(arm_claim_map, arm_id_) ||
264  partiallyClaimsArmJoints(arm_claim_map, arm_id_);
265 }
266 
267 // doSwitch runs on the main realtime thread.
268 void FrankaHW::doSwitch(const std::list<hardware_interface::ControllerInfo>& /* start_list */,
269  const std::list<hardware_interface::ControllerInfo>& /* stop_list */) {
271  reset();
272  controller_active_ = true;
273  }
274 }
275 
276 // prepareSwitch runs on the background message handling thread.
277 bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
278  const std::list<hardware_interface::ControllerInfo>& stop_list) {
279  ResourceWithClaimsMap start_resource_map = getResourceMap(start_list);
280  ArmClaimedMap start_arm_claim_map;
281  if (!getArmClaimedMap(start_resource_map, start_arm_claim_map)) {
282  ROS_ERROR("FrankaHW: Unknown interface claimed for starting!");
283  return false;
284  }
285 
286  ControlMode start_control_mode = getControlMode(arm_id_, start_arm_claim_map);
287 
288  ResourceWithClaimsMap stop_resource_map = getResourceMap(stop_list);
289  ArmClaimedMap stop_arm_claim_map;
290  if (!getArmClaimedMap(stop_resource_map, stop_arm_claim_map)) {
291  ROS_ERROR("FrankaHW: Unknown interface claimed for stopping!");
292  return false;
293  }
294  ControlMode stop_control_mode = getControlMode(arm_id_, stop_arm_claim_map);
295 
296  ControlMode requested_control_mode = current_control_mode_;
297  requested_control_mode &= ~stop_control_mode;
298  requested_control_mode |= start_control_mode;
299 
300  if (!setRunFunction(requested_control_mode, get_limit_rate_(), get_cutoff_frequency_(),
302  return false;
303  }
304 
305  if (current_control_mode_ != requested_control_mode) {
306  ROS_INFO_STREAM("FrankaHW: Prepared switching controllers to "
307  << requested_control_mode << " with parameters "
308  << "limit_rate=" << get_limit_rate_()
309  << ", cutoff_frequency=" << get_cutoff_frequency_()
310  << ", internal_controller=" << get_internal_controller_());
311  current_control_mode_ = requested_control_mode;
312  controller_active_ = false;
313  }
314 
315  return true;
316 }
317 
318 std::array<double, 7> FrankaHW::getJointPositionCommand() const noexcept {
320 }
321 
322 std::array<double, 7> FrankaHW::getJointVelocityCommand() const noexcept {
323  return velocity_joint_command_ros_.dq;
324 }
325 
326 std::array<double, 7> FrankaHW::getJointEffortCommand() const noexcept {
327  return effort_joint_command_ros_.tau_J;
328 }
329 
332 }
333 
335  std::string joint_limits_warning;
336  for (const auto& k_joint_name : joint_names_) {
337  try {
338  auto joint_handle = joint_state_interface_.getHandle(k_joint_name);
339  auto urdf_joint = urdf_model_.getJoint(k_joint_name);
341  if (getJointLimits(urdf_joint, joint_limits)) {
342  double joint_lower = joint_limits.min_position;
343  double joint_upper = joint_limits.max_position;
344  double joint_position = joint_handle.getPosition();
345  double dist = fmin(fabs(joint_position - joint_lower), fabs(joint_position - joint_upper));
346  if (dist < joint_limit_warning_threshold_) {
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) + ") ";
352  }
353  } else {
354  ROS_ERROR_STREAM_ONCE("FrankaHW: Could not parse joint limit for joint "
355  << k_joint_name << " for joint limit interfaces");
356  }
358  ROS_ERROR_STREAM_ONCE("FrankaHW::checkJointLimits Could not get joint handle " << k_joint_name
359  << " .\n"
360  << ex.what());
361  return;
362  }
363  }
364  if (!joint_limits_warning.empty()) {
365  ROS_WARN_THROTTLE(5, "FrankaHW: %s", joint_limits_warning.c_str());
366  }
367 }
368 
369 franka::Robot& FrankaHW::robot() const {
370  if (!initialized_ || !robot_) {
371  std::string error_message = !initialized_
372  ? "FrankaHW: Attempt to access robot before initialization!"
373  : "FrankaHW: Attempt to access disconnected robot!";
374  throw std::logic_error(error_message);
375  }
376  return *robot_;
377 }
378 
379 void FrankaHW::read(const ros::Time& /*time*/, const ros::Duration& /*period*/) {
380  std::lock_guard<std::mutex> ros_lock(ros_state_mutex_);
381  std::lock_guard<std::mutex> libfranka_lock(libfranka_state_mutex_);
383 }
384 
385 void FrankaHW::write(const ros::Time& /*time*/, const ros::Duration& /*period*/) {
386  std::lock_guard<std::mutex> ros_lock(ros_cmd_mutex_);
387  std::lock_guard<std::mutex> libfranka_lock(libfranka_cmd_mutex_);
393 }
394 
395 void FrankaHW::setupJointStateInterface(franka::RobotState& robot_state) {
396  for (size_t i = 0; i < joint_names_.size(); i++) {
397  hardware_interface::JointStateHandle joint_handle_q(joint_names_[i], &robot_state.q[i],
398  &robot_state.dq[i], &robot_state.tau_J[i]);
399  joint_state_interface_.registerHandle(joint_handle_q);
400  }
402 }
403 
404 void FrankaHW::setupFrankaStateInterface(franka::RobotState& robot_state) {
405  FrankaStateHandle franka_state_handle(arm_id_ + "_robot", robot_state);
406  franka_state_interface_.registerHandle(franka_state_handle);
408 }
409 
410 void FrankaHW::setupFrankaCartesianPoseInterface(franka::CartesianPose& pose_cartesian_command) {
411  FrankaCartesianPoseHandle franka_cartesian_pose_handle(
412  franka_state_interface_.getHandle(arm_id_ + "_robot"), pose_cartesian_command.O_T_EE,
413  pose_cartesian_command.elbow);
414  franka_pose_cartesian_interface_.registerHandle(franka_cartesian_pose_handle);
416 }
417 
419  franka::CartesianVelocities& velocity_cartesian_command) {
420  FrankaCartesianVelocityHandle franka_cartesian_velocity_handle(
421  franka_state_interface_.getHandle(arm_id_ + "_robot"), velocity_cartesian_command.O_dP_EE,
422  velocity_cartesian_command.elbow);
423  franka_velocity_cartesian_interface_.registerHandle(franka_cartesian_velocity_handle);
425 }
426 
427 void FrankaHW::setupFrankaModelInterface(franka::RobotState& robot_state) {
428  if (model_) {
429  franka_hw::FrankaModelHandle model_handle(arm_id_ + "_model", *model_, robot_state);
432  }
433 }
434 
435 bool FrankaHW::setRunFunction(const ControlMode& requested_control_mode,
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)>;
442 
443  switch (requested_control_mode) {
444  case ControlMode::None:
445  break;
447  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
448  robot.control(std::bind(&FrankaHW::controlCallback<franka::Torques>, this,
449  std::cref(effort_joint_command_libfranka_), ros_callback, _1, _2),
450  limit_rate, cutoff_frequency);
451  };
452  break;
454  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
455  robot.control(std::bind(&FrankaHW::controlCallback<franka::JointPositions>, this,
456  std::cref(position_joint_command_libfranka_), ros_callback, _1, _2),
457  internal_controller, limit_rate, cutoff_frequency);
458  };
459  break;
461  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
462  robot.control(std::bind(&FrankaHW::controlCallback<franka::JointVelocities>, this,
463  std::cref(velocity_joint_command_libfranka_), ros_callback, _1, _2),
464  internal_controller, limit_rate, cutoff_frequency);
465  };
466  break;
468  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
469  robot.control(std::bind(&FrankaHW::controlCallback<franka::CartesianPose>, this,
470  std::cref(pose_cartesian_command_libfranka_), ros_callback, _1, _2),
471  internal_controller, limit_rate, cutoff_frequency);
472  };
473  break;
475  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
476  robot.control(
477  std::bind(&FrankaHW::controlCallback<franka::CartesianVelocities>, this,
478  std::cref(velocity_cartesian_command_libfranka_), ros_callback, _1, _2),
479  internal_controller, limit_rate, cutoff_frequency);
480  };
481  break;
483  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
484  robot.control(std::bind(&FrankaHW::controlCallback<franka::Torques>, this,
485  std::cref(effort_joint_command_libfranka_), ros_callback, _1, _2),
486  std::bind(&FrankaHW::controlCallback<franka::JointPositions>, this,
487  std::cref(position_joint_command_libfranka_), ros_callback, _1, _2),
488  limit_rate, cutoff_frequency);
489  };
490  break;
492  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
493  robot.control(std::bind(&FrankaHW::controlCallback<franka::Torques>, this,
494  std::cref(effort_joint_command_libfranka_), ros_callback, _1, _2),
495  std::bind(&FrankaHW::controlCallback<franka::JointVelocities>, this,
496  std::cref(velocity_joint_command_libfranka_), ros_callback, _1, _2),
497  limit_rate, cutoff_frequency);
498  };
499  break;
501  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
502  robot.control(std::bind(&FrankaHW::controlCallback<franka::Torques>, this,
503  std::cref(effort_joint_command_libfranka_), ros_callback, _1, _2),
504  std::bind(&FrankaHW::controlCallback<franka::CartesianPose>, this,
505  std::cref(pose_cartesian_command_libfranka_), ros_callback, _1, _2),
506  limit_rate, cutoff_frequency);
507  };
508  break;
510  run_function_ = [=](franka::Robot& robot, Callback ros_callback) {
511  robot.control(
512  std::bind(&FrankaHW::controlCallback<franka::Torques>, this,
513  std::cref(effort_joint_command_libfranka_), ros_callback, _1, _2),
514  std::bind(&FrankaHW::controlCallback<franka::CartesianVelocities>, this,
515  std::cref(velocity_cartesian_command_libfranka_), ros_callback, _1, _2),
516  limit_rate, cutoff_frequency);
517  };
518  break;
519  default:
520  ROS_WARN("FrankaHW: No valid control mode selected; cannot switch controllers.");
521  return false;
522  }
523  return true;
524 }
525 
534  setupLimitInterface<joint_limits_interface::PositionJointSoftLimitsHandle>(
536  setupLimitInterface<joint_limits_interface::VelocityJointSoftLimitsHandle>(
538  setupLimitInterface<joint_limits_interface::EffortJointSoftLimitsHandle>(
544 }
545 
547  connect();
548  model_ = std::make_unique<franka_hw::Model>(robot_->loadModel());
549  update(robot_->readOnce());
550 }
551 
553  get_limit_rate_ = [robot_hw_nh]() {
554  bool rate_limiting;
555  robot_hw_nh.getParamCached("rate_limiting", rate_limiting);
556  return rate_limiting;
557  };
558 
559  get_internal_controller_ = [robot_hw_nh]() {
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;
567  } else {
568  ROS_WARN("Invalid internal_controller parameter provided, falling back to joint impedance");
569  controller_mode = franka::ControllerMode::kJointImpedance;
570  }
571  return controller_mode;
572  };
573 
574  get_cutoff_frequency_ = [robot_hw_nh]() {
575  double cutoff_frequency;
576  robot_hw_nh.getParamCached("cutoff_frequency", cutoff_frequency);
577  return cutoff_frequency;
578  };
579 }
580 
581 bool FrankaHW::commandHasNaN(const franka::Torques& command) {
582  return arrayHasNaN(command.tau_J);
583 }
584 
585 bool FrankaHW::commandHasNaN(const franka::JointPositions& command) {
586  return arrayHasNaN(command.q);
587 }
588 
589 bool FrankaHW::commandHasNaN(const franka::JointVelocities& command) {
590  return arrayHasNaN(command.dq);
591 }
592 
593 bool FrankaHW::commandHasNaN(const franka::CartesianPose& command) {
594  return arrayHasNaN(command.elbow) || arrayHasNaN(command.O_T_EE);
595 }
596 
597 bool FrankaHW::commandHasNaN(const franka::CartesianVelocities& command) {
598  return arrayHasNaN(command.elbow) || arrayHasNaN(command.O_dP_EE);
599 }
600 
601 std::vector<double> FrankaHW::getCollisionThresholds(const std::string& name,
602  const ros::NodeHandle& robot_hw_nh,
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()) {
607  std::string message;
608  for (const double& threshold : defaults) {
609  message += std::to_string(threshold);
610  message += " ";
611  }
612  ROS_INFO("No parameter %s found, using default values: %s", name.c_str(), message.c_str());
613  return defaults;
614  }
615  return thresholds;
616 }
617 
618 } // namespace franka_hw
franka_hw::FrankaHW::robotMutex
virtual std::mutex & robotMutex()
Getter for the mutex protecting access to the libfranka::robot class.
Definition: franka_hw.cpp:217
franka_hw::FrankaHW::libfranka_state_mutex_
std::mutex libfranka_state_mutex_
Definition: franka_hw.h:504
franka_hw::ControlMode::None
@ None
franka_hw::FrankaHW::setupJointCommandInterface
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...
Definition: franka_hw.h:408
franka_hw::FrankaHW::setupFrankaCartesianVelocityInterface
virtual void setupFrankaCartesianVelocityInterface(franka::CartesianVelocities &velocity_cartesian_command)
Configures and registers the command interface for Cartesian velocities in ros_control.
Definition: franka_hw.cpp:418
franka_hw::FrankaHW::franka_state_interface_
FrankaStateInterface franka_state_interface_
Definition: franka_hw.h:493
franka_hw::FrankaHW::initROSInterfaces
virtual void initROSInterfaces(ros::NodeHandle &robot_hw_nh)
Initializes the class in terms of ros_control interfaces.
Definition: franka_hw.cpp:526
franka_hw::FrankaHW::velocity_joint_interface_
hardware_interface::VelocityJointInterface velocity_joint_interface_
Definition: franka_hw.h:495
joint_limits_interface::JointLimits
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
franka_hw::FrankaHW::franka_pose_cartesian_interface_
FrankaPoseCartesianInterface franka_pose_cartesian_interface_
Definition: franka_hw.h:497
franka_hw::getArmClaimedMap
bool getArmClaimedMap(ResourceWithClaimsMap &resource_map, ArmClaimedMap &arm_claim_map)
Definition: resource_helpers.cpp:41
franka_hw::ControlMode
ControlMode
Definition: control_mode.h:10
franka_hw::FrankaHW::CollisionConfig::upper_force_thresholds_nominal
std::array< double, 6 > upper_force_thresholds_nominal
Definition: franka_hw.h:488
franka_hw::FrankaHW::setupFrankaCartesianPoseInterface
virtual void setupFrankaCartesianPoseInterface(franka::CartesianPose &pose_cartesian_command)
Configures and registers the command interface for Cartesian poses in ros_control.
Definition: franka_hw.cpp:410
HardwareResourceManager< JointStateHandle >::getHandle
JointStateHandle getHandle(const std::string &name)
hardware_interface::HardwareInterfaceException::what
const char * what() const noexcept override
franka_hw::FrankaHW::position_joint_command_libfranka_
franka::JointPositions position_joint_command_libfranka_
Definition: franka_hw.h:510
franka_hw::FrankaHW::get_limit_rate_
std::function< bool()> get_limit_rate_
Definition: franka_hw.h:539
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
hardware_interface::InterfaceManager::registerInterface
void registerInterface(T *iface)
franka_hw::FrankaHW::setRunFunction
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...
Definition: franka_hw.cpp:435
franka_hw::FrankaHW::setupParameterCallbacks
virtual void setupParameterCallbacks(ros::NodeHandle &robot_hw_nh)
Initializes the callbacks for on-the-fly reading the parameters for rate limiting,...
Definition: franka_hw.cpp:552
command
ROSLIB_DECL std::string command(const std::string &cmd)
getJointLimits
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, JointLimits &limits)
franka_hw::FrankaHW::setupFrankaModelInterface
virtual void setupFrankaModelInterface(franka::RobotState &robot_state)
Configures and registers the model interface offering kinematics and dynamics in ros_control.
Definition: franka_hw.cpp:427
joint_limits_interface::PositionJointSoftLimitsInterface::reset
void reset()
franka_hw::FrankaHW::controllerActive
virtual bool controllerActive() const noexcept
Indicates whether there is an active controller.
Definition: franka_hw.cpp:213
franka_hw::FrankaHW::getJointPositionCommand
virtual std::array< double, 7 > getJointPositionCommand() const noexcept
Gets the current joint position command.
Definition: franka_hw.cpp:318
franka_hw::FrankaHW::model_
std::unique_ptr< franka_hw::ModelBase > model_
Definition: franka_hw.h:525
franka_hw::FrankaHW::velocity_joint_command_ros_
franka::JointVelocities velocity_joint_command_ros_
Definition: franka_hw.h:518
franka_hw::FrankaHW::ros_cmd_mutex_
std::mutex ros_cmd_mutex_
Definition: franka_hw.h:516
franka_hw::FrankaHW::position_joint_command_ros_
franka::JointPositions position_joint_command_ros_
Definition: franka_hw.h:517
franka_hw::FrankaHW::write
virtual void write(const ros::Time &time, const ros::Duration &period) override
Writes data to the franka robot.
Definition: franka_hw.cpp:385
franka_hw::FrankaHW::CollisionConfig::upper_torque_thresholds_nominal
std::array< double, 7 > upper_torque_thresholds_nominal
Definition: franka_hw.h:484
joint_limits_interface::JointLimits::max_position
double max_position
franka_hw::FrankaCartesianVelocityHandle
Handle to read and command a Cartesian velocity.
Definition: franka_cartesian_command_interface.h:75
franka_hw::FrankaHW::velocity_cartesian_command_ros_
franka::CartesianVelocities velocity_cartesian_command_ros_
Definition: franka_hw.h:521
franka_hw::FrankaHW::getCollisionThresholds
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.
Definition: franka_hw.cpp:601
franka_hw::FrankaHW::velocity_cartesian_command_libfranka_
franka::CartesianVelocities velocity_cartesian_command_libfranka_
Definition: franka_hw.h:514
franka_hw::FrankaHW::setupJointStateInterface
virtual void setupJointStateInterface(franka::RobotState &robot_state)
Configures and registers the joint state interface in ros_control.
Definition: franka_hw.cpp:395
franka_hw::FrankaHW::effort_joint_command_ros_
franka::Torques effort_joint_command_ros_
Definition: franka_hw.h:519
franka_hw::FrankaHW::position_joint_limit_interface_
joint_limits_interface::PositionJointSoftLimitsInterface position_joint_limit_interface_
Definition: franka_hw.h:500
franka_hw::FrankaHW::franka_model_interface_
FrankaModelInterface franka_model_interface_
Definition: franka_hw.h:499
franka_hw::FrankaHW::update
virtual void update(const franka::RobotState &robot_state)
Updates the controller interfaces from the given robot state.
Definition: franka_hw.cpp:208
franka_hw::FrankaHW::realtime_config_
franka::RealtimeConfig realtime_config_
Definition: franka_hw.h:532
franka_hw::FrankaHW::velocity_joint_limit_interface_
joint_limits_interface::VelocityJointSoftLimitsInterface velocity_joint_limit_interface_
Definition: franka_hw.h:501
franka_hw::FrankaHW::pose_cartesian_command_libfranka_
franka::CartesianPose pose_cartesian_command_libfranka_
Definition: franka_hw.h:513
franka_hw::FrankaHW::effort_joint_interface_
hardware_interface::EffortJointInterface effort_joint_interface_
Definition: franka_hw.h:496
franka_hw::FrankaHW::CollisionConfig::lower_force_thresholds_nominal
std::array< double, 6 > lower_force_thresholds_nominal
Definition: franka_hw.h:487
franka_hw::FrankaHW::CollisionConfig::lower_torque_thresholds_nominal
std::array< double, 7 > lower_torque_thresholds_nominal
Definition: franka_hw.h:483
franka_hw::FrankaHW::getJointEffortCommand
virtual std::array< double, 7 > getJointEffortCommand() const noexcept
Gets the current joint torque command.
Definition: franka_hw.cpp:326
franka_hw::FrankaHW::arm_id_
std::string arm_id_
Definition: franka_hw.h:528
franka_hw::partiallyClaimsArmJoints
bool partiallyClaimsArmJoints(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
Definition: resource_helpers.cpp:187
franka_hw::FrankaStateHandle
Handle to read the complete state of a robot.
Definition: franka_state_interface.h:15
resource_helpers.h
franka_hw::FrankaHW::initRobot
virtual void initRobot()
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
Definition: franka_hw.cpp:546
franka_hw::FrankaHW::run_function_
std::function< void(franka::Robot &, Callback)> run_function_
Definition: franka_hw.h:541
franka_hw::FrankaHW::robot_ip_
std::string robot_ip_
Definition: franka_hw.h:529
franka_hw::FrankaHW::connect
virtual void connect()
Create a libfranka robot, connecting the hardware class to the master controller.
Definition: franka_hw.cpp:179
franka_hw::FrankaHW::effort_joint_command_libfranka_
franka::Torques effort_joint_command_libfranka_
Definition: franka_hw.h:512
franka_hw::FrankaHW::get_cutoff_frequency_
std::function< double()> get_cutoff_frequency_
Definition: franka_hw.h:540
franka_hw::FrankaHW::velocity_joint_command_libfranka_
franka::JointVelocities velocity_joint_command_libfranka_
Definition: franka_hw.h:511
franka_hw::FrankaHW::CollisionConfig::upper_torque_thresholds_acceleration
std::array< double, 7 > upper_torque_thresholds_acceleration
Definition: franka_hw.h:482
franka_hw::FrankaHW::checkJointLimits
virtual void checkJointLimits()
Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint...
Definition: franka_hw.cpp:334
franka_hw::FrankaHW::robot_mutex_
std::mutex robot_mutex_
Definition: franka_hw.h:523
franka_hw::FrankaHW::libfranka_cmd_mutex_
std::mutex libfranka_cmd_mutex_
Definition: franka_hw.h:509
franka_hw::operator<<
std::ostream & operator<<(std::ostream &ostream, ControlMode mode)
Definition: control_mode.cpp:12
franka_hw::FrankaHW::position_joint_interface_
hardware_interface::PositionJointInterface position_joint_interface_
Definition: franka_hw.h:494
franka_hw::FrankaHW::current_control_mode_
ControlMode current_control_mode_
Definition: franka_hw.h:536
hardware_interface::JointStateHandle
franka_hw::ControlMode::JointVelocity
@ JointVelocity
franka_hw::FrankaHW::CollisionConfig::lower_force_thresholds_acceleration
std::array< double, 6 > lower_force_thresholds_acceleration
Definition: franka_hw.h:485
urdf::Model::initParamWithNodeHandle
URDF_EXPORT bool initParamWithNodeHandle(const std::string &param, const ros::NodeHandle &nh=ros::NodeHandle())
franka_hw::FrankaHW::initParameters
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....
Definition: franka_hw.cpp:82
franka_hw.h
JointLimitsInterface< PositionJointSoftLimitsHandle >::enforceLimits
void enforceLimits(const ros::Duration &period)
franka_hw::FrankaHW::robot_state_ros_
franka::RobotState robot_state_ros_
Definition: franka_hw.h:507
franka_hw::FrankaHW::commandHasNaN
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.
Definition: franka_hw.cpp:581
franka_hw::getControlMode
ControlMode getControlMode(const std::string &arm_id, ArmClaimedMap &arm_claim_map)
Definition: resource_helpers.cpp:78
ROS_WARN
#define ROS_WARN(...)
franka_hw::FrankaHW::FrankaHW
FrankaHW()
Default constructor.
Definition: franka_hw.cpp:45
franka_hw::FrankaHW::connected
virtual bool connected()
Checks whether the hardware class is connected to a robot.
Definition: franka_hw.cpp:204
franka_hw::FrankaHW::robot_
std::unique_ptr< franka::Robot > robot_
Definition: franka_hw.h:524
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
franka_hw::FrankaHW::control
virtual void control(const std::function< bool(const ros::Time &, const ros::Duration &)> &ros_callback)
Runs the currently active controller in a realtime loop.
Definition: franka_hw.cpp:221
franka_hw::FrankaHW::joint_names_
std::array< std::string, 7 > joint_names_
Definition: franka_hw.h:527
franka_hw::ArmClaimedMap
std::map< std::string, ResourceClaims > ArmClaimedMap
Definition: resource_helpers.h:26
ResourceManager< JointStateHandle >::registerHandle
void registerHandle(const JointStateHandle &handle)
franka_hw::ResourceWithClaimsMap
std::map< std::string, std::vector< std::vector< std::string > >> ResourceWithClaimsMap
Definition: resource_helpers.h:16
franka_hw::FrankaHW::CollisionConfig::upper_force_thresholds_acceleration
std::array< double, 6 > upper_force_thresholds_acceleration
Definition: franka_hw.h:486
franka_hw::FrankaHW::disconnect
virtual bool disconnect()
Tries to disconnect the hardware class from the robot, freeing it for e.g.
Definition: franka_hw.cpp:194
franka_hw::FrankaCartesianPoseHandle
Handle to read and command a Cartesian pose.
Definition: franka_cartesian_command_interface.h:15
franka_hw::FrankaHW::enforceLimits
virtual void enforceLimits(const ros::Duration &period)
Enforces limits on position, velocity, and torque level.
Definition: franka_hw.cpp:245
franka_hw::FrankaHW::collision_config_
CollisionConfig collision_config_
Definition: franka_hw.h:491
franka_hw::FrankaHW::franka_velocity_cartesian_interface_
FrankaVelocityCartesianInterface franka_velocity_cartesian_interface_
Definition: franka_hw.h:498
franka_hw::FrankaHW::robot_state_libfranka_
franka::RobotState robot_state_libfranka_
Definition: franka_hw.h:506
hardware_interface::HardwareInterfaceException
franka_hw::FrankaHW::init
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
Definition: franka_hw.cpp:59
franka_hw::FrankaHW::CollisionConfig::lower_torque_thresholds_acceleration
std::array< double, 7 > lower_torque_thresholds_acceleration
Definition: franka_hw.h:481
joint_limits_interface::JointLimits::min_position
double min_position
ros::NodeHandle::getParamCached
bool getParamCached(const std::string &key, bool &b) const
ros::Time
franka_hw::FrankaHW::setupFrankaStateInterface
virtual void setupFrankaStateInterface(franka::RobotState &robot_state)
Configures and registers the state interface offering the full franka::RobotState in ros_control.
Definition: franka_hw.cpp:404
joint_limits_urdf.h
franka_hw::ControlMode::CartesianVelocity
@ CartesianVelocity
franka_hw
Definition: control_mode.h:8
franka_hw::FrankaHW::read
virtual void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the franka robot.
Definition: franka_hw.cpp:379
franka_hw::FrankaHW::joint_limit_warning_threshold_
double joint_limit_warning_threshold_
Definition: franka_hw.h:531
franka_hw::FrankaHW::arrayHasNaN
static bool arrayHasNaN(const std::array< double, size > &array)
Checks whether an array of doubles contains NaN values.
Definition: franka_hw.h:307
franka_hw::ControlMode::JointPosition
@ JointPosition
ROS_ERROR
#define ROS_ERROR(...)
franka_hw::FrankaHW::get_internal_controller_
std::function< franka::ControllerMode()> get_internal_controller_
Definition: franka_hw.h:538
franka_hw::FrankaHW::doSwitch
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &, const std::list< hardware_interface::ControllerInfo > &) override
Performs controller switching (real-time capable).
Definition: franka_hw.cpp:268
franka_hw::FrankaHW::initialized_
bool initialized_
Definition: franka_hw.h:534
franka_hw::FrankaHW::joint_state_interface_
hardware_interface::JointStateInterface joint_state_interface_
Definition: franka_hw.h:492
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
franka_hw::ControlMode::CartesianPose
@ CartesianPose
franka_hw::FrankaHW::pose_cartesian_command_ros_
franka::CartesianPose pose_cartesian_command_ros_
Definition: franka_hw.h:520
DurationBase< Duration >::toSec
double toSec() const
franka_hw::getResourceMap
ResourceWithClaimsMap getResourceMap(const std::list< hardware_interface::ControllerInfo > &info)
Definition: resource_helpers.cpp:23
franka_hw::FrankaHW::ros_state_mutex_
std::mutex ros_state_mutex_
Definition: franka_hw.h:505
franka_hw::FrankaHW::Callback
std::function< bool(const franka::RobotState &, franka::Duration)> Callback
Definition: franka_hw.h:311
ROS_INFO
#define ROS_INFO(...)
franka_hw::FrankaHW::getJointVelocityCommand
virtual std::array< double, 7 > getJointVelocityCommand() const noexcept
Gets the current joint velocity command.
Definition: franka_hw.cpp:322
franka_hw::FrankaModelHandle
Handle to perform calculations using the dynamic model of a robot.
Definition: franka_model_interface.h:19
franka_hw::hasConflictingMultiClaim
bool hasConflictingMultiClaim(const ResourceWithClaimsMap &resource_map)
Definition: resource_helpers.cpp:138
franka_hw::FrankaHW::robot
virtual franka::Robot & robot() const
Getter for the libfranka robot instance.
Definition: franka_hw.cpp:369
ros::Duration
franka_hw::FrankaHW::reset
virtual void reset()
Resets the limit interfaces.
Definition: franka_hw.cpp:330
franka_hw::FrankaHW::controller_active_
std::atomic_bool controller_active_
Definition: franka_hw.h:535
franka_hw::FrankaHW::effort_joint_limit_interface_
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_
Definition: franka_hw.h:502
franka_hw::ControlMode::JointTorque
@ JointTorque
franka_hw::FrankaHW::prepareSwitch
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).
Definition: franka_hw.cpp:277
ROS_ERROR_STREAM_ONCE
#define ROS_ERROR_STREAM_ONCE(args)
ros::NodeHandle
franka_hw::hasConflictingJointAndCartesianClaim
bool hasConflictingJointAndCartesianClaim(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
Definition: resource_helpers.cpp:168
franka_hw::FrankaHW::checkForConflict
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.
Definition: franka_hw.cpp:253
franka_hw::FrankaHW::urdf_model_
urdf::Model urdf_model_
Definition: franka_hw.h:530


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21