franka_hw_sim.cpp
Go to the documentation of this file.
1 #include <angles/angles.h>
2 #include <controller_manager_msgs/ListControllers.h>
3 #include <controller_manager_msgs/SwitchController.h>
4 #include <franka/duration.h>
8 #include <franka_hw/franka_hw.h>
9 #include <franka_hw/services.h>
10 #include <franka_msgs/SetEEFrame.h>
11 #include <franka_msgs/SetForceTorqueCollisionBehavior.h>
12 #include <franka_msgs/SetKFrame.h>
13 #include <franka_msgs/SetLoad.h>
16 #include <std_msgs/Bool.h>
17 #include <std_srvs/SetBool.h>
18 #include <Eigen/Dense>
19 #include <boost/algorithm/clamp.hpp>
20 #include <boost/optional.hpp>
21 #include <iostream>
22 #include <sstream>
23 #include <string>
24 
25 namespace franka_gazebo {
26 
28 using boost::sml::state;
29 
30 FrankaHWSim::FrankaHWSim() : sm_(this->robot_state_, this->joints_) {}
31 
32 bool FrankaHWSim::initSim(const std::string& robot_namespace,
33  ros::NodeHandle model_nh,
34  gazebo::physics::ModelPtr parent,
35  const urdf::Model* const urdf,
36  std::vector<transmission_interface::TransmissionInfo> transmissions) {
37  model_nh.param<std::string>("arm_id", this->arm_id_, robot_namespace);
38  if (this->arm_id_ != robot_namespace) {
40  "franka_hw_sim",
41  "Caution: Robot names differ! Read 'arm_id: "
42  << this->arm_id_ << "' from parameter server but URDF defines '<robotNamespace>"
43  << robot_namespace << "</robotNamespace>'. Will use '" << this->arm_id_ << "'!");
44  }
45 
46  this->robot_ = parent;
47  this->robot_initialized_ = false;
48 
49  this->robot_initialized_pub_ = model_nh.advertise<std_msgs::Bool>("initialized", 1);
50  std_msgs::Bool msg;
51  msg.data = static_cast<decltype(msg.data)>(false);
53 
54  this->action_recovery_ = std::make_unique<SimpleActionServer<franka_msgs::ErrorRecoveryAction>>(
55  model_nh, "franka_control/error_recovery",
56  [&](const franka_msgs::ErrorRecoveryGoalConstPtr& goal) {
58  ROS_WARN_STREAM_NAMED("franka_hw_sim",
59  "Cannot recover errors since the user stop seems still pressed");
60  this->action_recovery_->setSucceeded();
61  return;
62  }
63  try {
65  ROS_INFO_NAMED("franka_hw_sim", "Recovered from error");
66  this->sm_.process_event(ErrorRecovery());
67  this->action_recovery_->setSucceeded();
68  } catch (const std::runtime_error& e) {
69  ROS_WARN_STREAM_NAMED("franka_hw_sim", "Error recovery failed: " << e.what());
70  this->action_recovery_->setAborted();
71  }
72  },
73  false);
74  this->action_recovery_->start();
75 
76 #if GAZEBO_MAJOR_VERSION >= 8
77  gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->Physics();
78 #else
79  gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->GetPhysicsEngine();
80 #endif
81 
82  ROS_INFO_STREAM_NAMED("franka_hw_sim", "Using physics type " << physics->GetType());
83 
84  // Retrieve initial gravity vector from Gazebo
85  // NOTE: Can be overwritten by the user via the 'gravity_vector' ROS parameter.
86  auto gravity = physics->World()->Gravity();
87  this->gravity_earth_ = {gravity.X(), gravity.Y(), gravity.Z()};
88 
89  model_nh.param<double>("tau_ext_lowpass_filter", this->tau_ext_lowpass_filter_,
91 
92  // Generate a list of franka_gazebo::Joint to store all relevant information
93  for (const auto& transmission : transmissions) {
94  if (transmission.type_ != "transmission_interface/SimpleTransmission") {
95  continue;
96  }
97  if (transmission.joints_.empty()) {
98  ROS_WARN_STREAM_NAMED("franka_hw_sim",
99  "Transmission " << transmission.name_ << " has no associated joints.");
100  return false;
101  }
102  if (transmission.joints_.size() > 1) {
104  "franka_hw_sim",
105  "Transmission "
106  << transmission.name_
107  << " has more than one joint. Currently the franka robot hardware simulation "
108  << " interface only supports one.");
109  return false;
110  }
111 
112  // Fill a 'Joint' struct which holds all necessary data
113  auto joint = std::make_shared<franka_gazebo::Joint>();
114  joint->name = transmission.joints_[0].name_;
115  if (urdf == nullptr) {
117  "franka_hw_sim", "Could not find any URDF model. Was it loaded on the parameter server?");
118  return false;
119  }
120  auto urdf_joint = urdf->getJoint(joint->name);
121  if (not urdf_joint) {
122  ROS_ERROR_STREAM_NAMED("franka_hw_sim",
123  "Could not get joint '" << joint->name << "' from URDF");
124  return false;
125  }
126  joint->type = urdf_joint->type;
127  joint_limits_interface::getJointLimits(urdf_joint, joint->limits);
128  joint->axis = Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z);
129 
130  // Get a handle to the underlying Gazebo Joint
131  gazebo::physics::JointPtr handle = parent->GetJoint(joint->name);
132  if (not handle) {
133  ROS_ERROR_STREAM_NAMED("franka_hw_sim", "This robot has a joint named '"
134  << joint->name
135  << "' which is not in the gazebo model.");
136  return false;
137  }
138  joint->handle = handle;
139  // set the control method for finger joints to effort
140  if (joint->name.find(arm_id_ + "_finger_joint") != std::string::npos) {
141  joint->control_method = EFFORT;
142  }
143  this->joints_.emplace(joint->name, joint);
144  }
145 
146  // After the joint data containers have been fully initialized and their memory address don't
147  // change anymore, get the respective addresses to pass them to the handles
148 
149  for (auto& pair : this->joints_) {
150  initJointStateHandle(pair.second);
151  }
152 
153  // Register all supported command interfaces
154  for (const auto& transmission : transmissions) {
155  for (const auto& k_interface : transmission.joints_[0].hardware_interfaces_) {
156  auto joint = this->joints_[transmission.joints_[0].name_];
157  if (transmission.type_ == "transmission_interface/SimpleTransmission") {
158  ROS_INFO_STREAM_NAMED("franka_hw_sim", "Found transmission interface of joint '"
159  << joint->name << "': " << k_interface);
160  if (k_interface == "hardware_interface/EffortJointInterface") {
162  continue;
163  }
164  if (k_interface == "hardware_interface/PositionJointInterface") {
165  // Initiate position motion generator (PID controller)
166  joint->position_controller.initParam(robot_namespace +
167  "/motion_generators/position/gains/" + joint->name);
169  continue;
170  }
171  if (k_interface == "hardware_interface/VelocityJointInterface") {
172  // Initiate velocity motion generator (PID controller)
173  joint->velocity_controller.initParam(robot_namespace +
174  "/motion_generators/velocity/gains/" + joint->name);
176  continue;
177  }
178  }
179 
180  if (transmission.type_ == "franka_hw/FrankaStateInterface") {
181  ROS_INFO_STREAM_NAMED("franka_hw_sim",
182  "Found transmission interface '" << transmission.type_ << "'");
183  try {
184  initFrankaStateHandle(this->arm_id_, *urdf, transmission);
185  continue;
186 
187  } catch (const std::invalid_argument& e) {
188  ROS_ERROR_STREAM_NAMED("franka_hw_sim", e.what());
189  return false;
190  }
191  }
192 
193  if (transmission.type_ == "franka_hw/FrankaModelInterface") {
194  ROS_INFO_STREAM_NAMED("franka_hw_sim",
195  "Found transmission interface '" << transmission.type_ << "'");
196  double singularity_threshold;
197  model_nh.param<double>("singularity_warning_threshold", singularity_threshold, -1);
198  try {
199  initFrankaModelHandle(this->arm_id_, *urdf, transmission, singularity_threshold);
200  continue;
201 
202  } catch (const std::invalid_argument& e) {
203  ROS_ERROR_STREAM_NAMED("franka_hw_sim", e.what());
204  return false;
205  }
206  }
207  ROS_WARN_STREAM_NAMED("franka_hw_sim", "Unsupported transmission interface of joint '"
208  << joint->name << "': " << k_interface);
209  }
210  }
211 
212  // After all handles have been assigned to interfaces, register them
213  assert(this->eji_.getNames().size() >= 7);
214  assert(this->pji_.getNames().size() == 7);
215  assert(this->vji_.getNames().size() == 7);
216  assert(this->jsi_.getNames().size() >= 7);
217  assert(this->fsi_.getNames().size() == 1);
218  assert(this->fmi_.getNames().size() == 1);
219 
220  registerInterface(&this->eji_);
221  registerInterface(&this->pji_);
222  registerInterface(&this->vji_);
223  registerInterface(&this->jsi_);
224  registerInterface(&this->fsi_);
225  registerInterface(&this->fmi_);
226 
227  // Initialize ROS Services
228  initServices(model_nh);
229  verifier_ = std::make_unique<ControllerVerifier>(joints_, arm_id_);
230  return readParameters(model_nh, *urdf);
231 }
232 
233 void FrankaHWSim::initJointStateHandle(const std::shared_ptr<franka_gazebo::Joint>& joint) {
234  this->jsi_.registerHandle(hardware_interface::JointStateHandle(joint->name, &joint->position,
235  &joint->velocity, &joint->effort));
236 }
237 
238 void FrankaHWSim::initEffortCommandHandle(const std::shared_ptr<franka_gazebo::Joint>& joint) {
239  this->eji_.registerHandle(
240  hardware_interface::JointHandle(this->jsi_.getHandle(joint->name), &joint->command));
241 }
242 
243 void FrankaHWSim::initPositionCommandHandle(const std::shared_ptr<franka_gazebo::Joint>& joint) {
244  this->pji_.registerHandle(
245  hardware_interface::JointHandle(this->jsi_.getHandle(joint->name), &joint->desired_position));
246 }
247 
248 void FrankaHWSim::initVelocityCommandHandle(const std::shared_ptr<franka_gazebo::Joint>& joint) {
249  this->vji_.registerHandle(
250  hardware_interface::JointHandle(this->jsi_.getHandle(joint->name), &joint->desired_velocity));
251 }
252 
254  const std::string& robot,
255  const urdf::Model& urdf,
256  const transmission_interface::TransmissionInfo& transmission) {
257  if (transmission.joints_.size() != 7) {
258  throw std::invalid_argument(
259  "Cannot create franka_hw/FrankaStateInterface for robot '" + robot + "_robot' because " +
260  std::to_string(transmission.joints_.size()) +
261  " joints were found beneath the <transmission> tag, but 7 are required.");
262  }
263 
264  // Initialize robot_mode to "Idle". Once a controller is started, we will switch to "Move"
266 
267  // Check if all joints defined in the <transmission> actually exist in the URDF
268  for (const auto& joint : transmission.joints_) {
269  if (not urdf.getJoint(joint.name_)) {
270  throw std::invalid_argument("Cannot create franka_hw/FrankaStateInterface for robot '" +
271  robot + "_robot' because the specified joint '" + joint.name_ +
272  "' in the <transmission> tag cannot be found in the URDF");
273  }
274  ROS_DEBUG_STREAM_NAMED("franka_hw_sim",
275  "Found joint " << joint.name_ << " to belong to a Panda robot");
276  }
277  this->fsi_.registerHandle(franka_hw::FrankaStateHandle(robot + "_robot", this->robot_state_));
278 }
279 
281  const std::string& robot,
282  const urdf::Model& urdf,
283  const transmission_interface::TransmissionInfo& transmission,
284  double singularity_threshold) {
285  if (transmission.joints_.size() != 2) {
286  throw std::invalid_argument(
287  "Cannot create franka_hw/FrankaModelInterface for robot '" + robot + "_model' because " +
288  std::to_string(transmission.joints_.size()) +
289  " joints were found beneath the <transmission> tag, but 2 are required.");
290  }
291 
292  for (const auto& joint : transmission.joints_) {
293  if (not urdf.getJoint(joint.name_)) {
294  if (not urdf.getJoint(joint.name_)) {
295  throw std::invalid_argument("Cannot create franka_hw/FrankaModelInterface for robot '" +
296  robot + "_model' because the specified joint '" + joint.name_ +
297  "' in the <transmission> tag cannot be found in the URDF");
298  }
299  }
300  }
301  auto root =
302  std::find_if(transmission.joints_.begin(), transmission.joints_.end(),
303  [&](const transmission_interface::JointInfo& i) { return i.role_ == "root"; });
304  if (root == transmission.joints_.end()) {
305  throw std::invalid_argument("Cannot create franka_hw/FrankaModelInterface for robot '" + robot +
306  "_model' because no <joint> with <role>root</root> can be found "
307  "in the <transmission>");
308  }
309  auto tip =
310  std::find_if(transmission.joints_.begin(), transmission.joints_.end(),
311  [&](const transmission_interface::JointInfo& i) { return i.role_ == "tip"; });
312  if (tip == transmission.joints_.end()) {
313  throw std::invalid_argument("Cannot create franka_hw/FrankaModelInterface for robot '" + robot +
314  "_model' because no <joint> with <role>tip</role> can be found "
315  "in the <transmission>");
316  }
317  try {
318  auto root_link = urdf.getJoint(root->name_)->parent_link_name;
319  auto tip_link = urdf.getJoint(tip->name_)->child_link_name;
320 
321  this->model_ =
322  std::make_unique<franka_gazebo::ModelKDL>(urdf, root_link, tip_link, singularity_threshold);
323 
324  } catch (const std::invalid_argument& e) {
325  throw std::invalid_argument("Cannot create franka_hw/FrankaModelInterface for robot '" + robot +
326  "_model'. " + e.what());
327  }
328  this->fmi_.registerHandle(
329  franka_hw::FrankaModelHandle(robot + "_model", *this->model_, this->robot_state_));
330 }
331 
333  this->service_set_ee_ =
334  nh.advertiseService<franka_msgs::SetEEFrame::Request, franka_msgs::SetEEFrame::Response>(
335  "franka_control/set_EE_frame", [&](auto& request, auto& response) {
336  ROS_INFO_STREAM_NAMED("franka_hw_sim",
337  this->arm_id_ << ": Setting NE_T_EE transformation");
338  std::copy(request.NE_T_EE.cbegin(), request.NE_T_EE.cend(),
339  this->robot_state_.NE_T_EE.begin());
340  this->updateRobotStateDynamics();
341  response.success = true;
342  return true;
343  });
344  this->service_set_k_ = franka_hw::advertiseService<franka_msgs::SetKFrame>(
345  nh, "franka_control/set_K_frame", [&](auto& request, auto& response) {
346  ROS_INFO_STREAM_NAMED("franka_hw_sim", this->arm_id_ << ": Setting EE_T_K transformation");
347  std::copy(request.EE_T_K.cbegin(), request.EE_T_K.cend(),
348  this->robot_state_.EE_T_K.begin());
349  this->updateRobotStateDynamics();
350  response.success = true;
351  return true;
352  });
353  this->service_set_load_ = franka_hw::advertiseService<franka_msgs::SetLoad>(
354  nh, "franka_control/set_load", [&](auto& request, auto& response) {
355  ROS_INFO_STREAM_NAMED("franka_hw_sim", this->arm_id_ << ": Setting Load");
356  this->robot_state_.m_load = request.mass;
357  std::copy(request.F_x_center_load.cbegin(), request.F_x_center_load.cend(),
358  this->robot_state_.F_x_Cload.begin());
359  std::copy(request.load_inertia.cbegin(), request.load_inertia.cend(),
360  this->robot_state_.I_load.begin());
361  this->updateRobotStateDynamics();
362  response.success = true;
363  return true;
364  });
366  franka_hw::advertiseService<franka_msgs::SetForceTorqueCollisionBehavior>(
367  nh, "franka_control/set_force_torque_collision_behavior",
368  [&](auto& request, auto& response) {
369  ROS_INFO_STREAM_NAMED("franka_hw_sim", this->arm_id_ << ": Setting Collision Behavior");
370 
371  for (int i = 0; i < 7; i++) {
372  std::string name = this->arm_id_ + "_joint" + std::to_string(i + 1);
373  this->joints_[name]->contact_threshold =
374  request.lower_torque_thresholds_nominal.at(i);
375  this->joints_[name]->collision_threshold =
376  request.upper_torque_thresholds_nominal.at(i);
377  }
378 
379  std::move(request.lower_force_thresholds_nominal.begin(),
380  request.lower_force_thresholds_nominal.end(),
381  this->lower_force_thresholds_nominal_.begin());
382  std::move(request.upper_force_thresholds_nominal.begin(),
383  request.upper_force_thresholds_nominal.end(),
384  this->upper_force_thresholds_nominal_.begin());
385 
386  response.success = true;
387  return true;
388  });
389  this->service_user_stop_ =
390  nh.advertiseService<std_srvs::SetBool::Request, std_srvs::SetBool::Response>(
391  "franka_control/set_user_stop", [&](auto& request, auto& response) {
392  this->sm_.process_event(UserStop{static_cast<bool>(request.data)});
393  response.success = true;
394  return true;
395  });
396  this->service_controller_list_ = nh.serviceClient<controller_manager_msgs::ListControllers>(
397  "controller_manager/list_controllers");
398  this->service_controller_switch_ = nh.serviceClient<controller_manager_msgs::SwitchController>(
399  "controller_manager/switch_controller");
400 }
401 
403  // Restart controllers by stopping and starting all running ones
406  throw std::runtime_error("Cannot find service '" + name +
407  "'. Is the controller_manager running?");
408  }
409 
410  controller_manager_msgs::ListControllers list;
411  if (not this->service_controller_list_.call(list)) {
412  throw std::runtime_error("Service call '" + name + "' failed");
413  }
414 
415  controller_manager_msgs::SwitchController swtch;
416  for (const auto& controller : list.response.controller) {
417  if (controller.state != "running") {
418  continue;
419  }
420  swtch.request.stop_controllers.push_back(controller.name);
421  swtch.request.start_controllers.push_back(controller.name);
422  }
423  swtch.request.start_asap = static_cast<decltype(swtch.request.start_asap)>(true);
424  swtch.request.strictness = controller_manager_msgs::SwitchControllerRequest::STRICT;
425  if (not this->service_controller_switch_.call(swtch) or
426  not static_cast<bool>(swtch.response.ok)) {
427  throw std::runtime_error("Service call '" + this->service_controller_switch_.getService() +
428  "' failed");
429  }
430 }
431 
433  for (const auto& pair : this->joints_) {
434  auto joint = pair.second;
435  joint->update(period);
436  }
437  this->updateRobotState(time);
438 }
439 
440 double FrankaHWSim::positionControl(Joint& joint, double setpoint, const ros::Duration& period) {
441  double error;
442  const double kJointLowerLimit = joint.limits.min_position;
443  const double kJointUpperLimit = joint.limits.max_position;
444  switch (joint.type) {
445  case urdf::Joint::REVOLUTE:
446  angles::shortest_angular_distance_with_limits(joint.position, setpoint, kJointLowerLimit,
447  kJointUpperLimit, error);
448  break;
449  case urdf::Joint::PRISMATIC:
450  error =
451  boost::algorithm::clamp(setpoint - joint.position, kJointLowerLimit, kJointUpperLimit);
452  break;
453  default:
454  std::string error_message =
455  "Only revolute or prismatic joints are allowed for position control right now";
456  ROS_FATAL("%s", error_message.c_str());
457  throw std::invalid_argument(error_message);
458  }
459 
460  return boost::algorithm::clamp(joint.position_controller.computeCommand(error, period),
461  -joint.limits.max_effort, joint.limits.max_effort);
462 }
463 
464 double FrankaHWSim::velocityControl(Joint& joint, double setpoint, const ros::Duration& period) {
465  return boost::algorithm::clamp(
466  joint.velocity_controller.computeCommand(setpoint - joint.velocity, period),
467  -joint.limits.max_effort, joint.limits.max_effort);
468 }
469 
471  auto g = this->model_->gravity(this->robot_state_, this->gravity_earth_);
472 
473  for (auto& pair : this->joints_) {
474  auto joint = pair.second;
475 
476  // Retrieve effort control command
477  double effort = 0;
478 
479  // Finger joints must still be controllable from franka_gripper_sim controller
480  if (not sm_.is(state<Move>) and not contains(pair.first, "finger_joint")) {
481  effort = positionControl(*joint, joint->stop_position, period);
482  } else if (joint->control_method == POSITION) {
483  effort = positionControl(*joint, joint->desired_position, period);
484  } else if (joint->control_method == VELOCITY) {
485  velocityControl(*joint, joint->desired_velocity, period);
486  } else if (joint->control_method == EFFORT) {
487  // Feed-forward commands in effort control
488  effort = joint->command;
489  }
490 
491  // Check if this joint is affected by gravity compensation
492  std::string prefix = this->arm_id_ + "_joint";
493  if (pair.first.rfind(prefix, 0) != std::string::npos) {
494  int i = std::stoi(pair.first.substr(prefix.size())) - 1;
495  joint->gravity = g.at(i);
496  }
497  effort += joint->gravity;
498 
499  // Send control effort control command
500  if (not std::isfinite(effort)) {
501  ROS_WARN_STREAM_NAMED("franka_hw_sim",
502  "Command for " << joint->name << "is not finite, won't send to robot");
503  continue;
504  }
505  joint->handle->SetForce(0, effort);
506  }
507 }
508 
509 void FrankaHWSim::eStopActive(bool /* active */) {}
510 
512  try {
513  guessEndEffector(nh, urdf);
514 
515  nh.param<double>("m_load", this->robot_state_.m_load, 0);
516 
517  std::string I_load; // NOLINT [readability-identifier-naming]
518  nh.param<std::string>("I_load", I_load, "0 0 0 0 0 0 0 0 0");
519  this->robot_state_.I_load = readArray<9>(I_load, "I_load");
520 
521  std::string F_x_Cload; // NOLINT [readability-identifier-naming]
522  nh.param<std::string>("F_x_Cload", F_x_Cload, "0 0 0");
523  this->robot_state_.F_x_Cload = readArray<3>(F_x_Cload, "F_x_Cload");
524 
525  std::string NE_T_EE; // NOLINT [readability-identifier-naming]
526  nh.param<std::string>("NE_T_EE", NE_T_EE, "1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1");
527  this->robot_state_.NE_T_EE = readArray<16>(NE_T_EE, "NE_T_EE");
528 
529  std::string EE_T_K; // NOLINT [readability-identifier-naming]
530  nh.param<std::string>("EE_T_K", EE_T_K, "1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1");
531  this->robot_state_.EE_T_K = readArray<16>(EE_T_K, "EE_T_K");
532 
533  std::string gravity_vector;
534  if (nh.getParam("gravity_vector", gravity_vector)) {
535  this->gravity_earth_ = readArray<3>(gravity_vector, "gravity_vector");
536  }
537 
538  // Only nominal cases supported for now
539  std::vector<double> lower_torque_thresholds = franka_hw::FrankaHW::getCollisionThresholds(
540  "lower_torque_thresholds_nominal", nh, {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
541 
542  std::vector<double> upper_torque_thresholds = franka_hw::FrankaHW::getCollisionThresholds(
543  "upper_torque_thresholds_nominal", nh, {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
544 
546  "lower_force_thresholds_nominal", nh, {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
548  "upper_force_thresholds_nominal", nh, {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
549 
550  for (int i = 0; i < 7; i++) {
551  std::string name = this->arm_id_ + "_joint" + std::to_string(i + 1);
552  this->joints_[name]->contact_threshold = lower_torque_thresholds.at(i);
553  this->joints_[name]->collision_threshold = upper_torque_thresholds.at(i);
554  }
555 
556  } catch (const std::invalid_argument& e) {
557  ROS_ERROR_STREAM_NAMED("franka_hw_sim", e.what());
558  return false;
559  }
561  return true;
562 }
563 
565  auto hand_link = this->arm_id_ + "_hand";
566  auto hand = urdf.getLink(hand_link);
567  if (hand != nullptr) {
568  ROS_INFO_STREAM_NAMED("franka_hw_sim",
569  "Found link '" << hand_link
570  << "' in URDF. Assuming it is defining the kinematics & "
571  "inertias of a Franka Hand Gripper.");
572  }
573 
574  // By absolute default unless URDF or ROS params say otherwise, assume no end-effector.
575  double def_m_ee = 0;
576  std::string def_i_ee = "0.0 0 0 0 0.0 0 0 0 0.0";
577  std::string def_f_x_cee = "0 0 0";
578  std::string def_f_t_ne = "1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1";
579  if (not nh.hasParam("F_T_NE") and hand != nullptr) {
580  // NOTE: We cannot interprete the Joint pose from the URDF directly, because
581  // its <arm_id>_link is mounted at the flange directly and not at NE
582  def_f_t_ne = "0.7071 -0.7071 0 0 0.7071 0.7071 0 0 0 0 1 0 0 0 0.1034 1";
583  }
584  std::string F_T_NE; // NOLINT [readability-identifier-naming]
585  nh.param<std::string>("F_T_NE", F_T_NE, def_f_t_ne);
586  this->robot_state_.F_T_NE = readArray<16>(F_T_NE, "F_T_NE");
587 
588  if (not nh.hasParam("m_ee") and hand != nullptr) {
589  if (hand->inertial == nullptr) {
590  throw std::invalid_argument("Trying to use inertia of " + hand_link +
591  " but this link has no <inertial> tag defined in it.");
592  }
593  def_m_ee = hand->inertial->mass;
594  }
595  nh.param<double>("m_ee", this->robot_state_.m_ee, def_m_ee);
596 
597  if (not nh.hasParam("I_ee") and hand != nullptr) {
598  if (hand->inertial == nullptr) {
599  throw std::invalid_argument("Trying to use inertia of " + hand_link +
600  " but this link has no <inertial> tag defined in it.");
601  }
602  // clang-format off
603  def_i_ee = std::to_string(hand->inertial->ixx) + " " + std::to_string(hand->inertial->ixy) + " " + std::to_string(hand->inertial->ixz) + " "
604  + std::to_string(hand->inertial->ixy) + " " + std::to_string(hand->inertial->iyy) + " " + std::to_string(hand->inertial->iyz) + " "
605  + std::to_string(hand->inertial->ixz) + " " + std::to_string(hand->inertial->iyz) + " " + std::to_string(hand->inertial->izz);
606  // clang-format on
607  }
608  std::string I_ee; // NOLINT [readability-identifier-naming]
609  nh.param<std::string>("I_ee", I_ee, def_i_ee);
610  this->robot_state_.I_ee = readArray<9>(I_ee, "I_ee");
611 
612  if (not nh.hasParam("F_x_Cee") and hand != nullptr) {
613  if (hand->inertial == nullptr) {
614  throw std::invalid_argument("Trying to use inertia of " + hand_link +
615  " but this link has no <inertial> tag defined in it.");
616  }
617  def_f_x_cee = std::to_string(hand->inertial->origin.position.x) + " " +
618  std::to_string(hand->inertial->origin.position.y) + " " +
619  std::to_string(hand->inertial->origin.position.z);
620  }
621  std::string F_x_Cee; // NOLINT [readability-identifier-naming]
622  nh.param<std::string>("F_x_Cee", F_x_Cee, def_f_x_cee);
623  this->robot_state_.F_x_Cee = readArray<3>(F_x_Cee, "F_x_Cee");
624 }
625 
628 
629  Eigen::Map<Eigen::Matrix4d>(this->robot_state_.F_T_EE.data()) =
630  Eigen::Matrix4d(this->robot_state_.F_T_NE.data()) *
631  Eigen::Matrix4d(this->robot_state_.NE_T_EE.data());
632 
633  Eigen::Map<Eigen::Matrix3d>(this->robot_state_.I_total.data()) =
634  shiftInertiaTensor(Eigen::Matrix3d(this->robot_state_.I_ee.data()), this->robot_state_.m_ee,
635  Eigen::Vector3d(this->robot_state_.F_x_Cload.data()));
636 }
637 
639  // This is ensured, because a FrankaStateInterface checks for at least seven joints in the URDF
640  assert(this->joints_.size() >= 7);
641 
642  auto mode = this->robot_state_.robot_mode;
643  for (int i = 0; i < 7; i++) {
644  std::string name = this->arm_id_ + "_joint" + std::to_string(i + 1);
645  const auto& joint = this->joints_.at(name);
646  this->robot_state_.q[i] = joint->position;
647  this->robot_state_.dq[i] = joint->velocity;
648  this->robot_state_.tau_J[i] = joint->effort;
649  this->robot_state_.dtau_J[i] = joint->jerk;
650 
651  this->robot_state_.q_d[i] = joint->getDesiredPosition(mode);
652  this->robot_state_.dq_d[i] = joint->getDesiredVelocity(mode);
653  this->robot_state_.ddq_d[i] = joint->getDesiredAcceleration(mode);
654  this->robot_state_.tau_J_d[i] = joint->getDesiredTorque(mode);
655 
656  // For now we assume no flexible joints
657  this->robot_state_.theta[i] = joint->position;
658  this->robot_state_.dtheta[i] = joint->velocity;
659 
660  // first time initialization of the desired position
661  if (not this->robot_initialized_) {
662  joint->desired_position = joint->position;
663  joint->stop_position = joint->position;
664  }
665 
666  if (this->robot_initialized_) {
667  double tau_ext = joint->effort - joint->command + joint->gravity;
668 
669  // Exponential moving average filter from tau_ext -> tau_ext_hat_filtered
671  this->tau_ext_lowpass_filter_ * tau_ext +
673  }
674 
675  this->robot_state_.joint_contact[i] = static_cast<double>(joint->isInContact());
676  this->robot_state_.joint_collision[i] = static_cast<double>(joint->isInCollision());
677  }
678 
679  // Calculate estimated wrenches in Task frame from external joint torques with jacobians
680  Eigen::Map<Eigen::Matrix<double, 7, 1>> tau_ext(this->robot_state_.tau_ext_hat_filtered.data());
681  Eigen::MatrixXd j0_transpose_pinv;
682  Eigen::MatrixXd jk_transpose_pinv;
683  Eigen::Matrix<double, 6, 7> j0(
684  this->model_->zeroJacobian(franka::Frame::kStiffness, this->robot_state_).data());
685  Eigen::Matrix<double, 6, 7> jk(
686  this->model_->bodyJacobian(franka::Frame::kStiffness, this->robot_state_).data());
687  franka_example_controllers::pseudoInverse(j0.transpose(), j0_transpose_pinv);
688  franka_example_controllers::pseudoInverse(jk.transpose(), jk_transpose_pinv);
689 
690  Eigen::VectorXd f_ext_0 = j0_transpose_pinv * tau_ext;
691  Eigen::VectorXd f_ext_k = jk_transpose_pinv * tau_ext;
692  Eigen::VectorXd::Map(&this->robot_state_.O_F_ext_hat_K[0], 6) = f_ext_0;
693  Eigen::VectorXd::Map(&this->robot_state_.K_F_ext_hat_K[0], 6) = f_ext_k;
694 
695  for (int i = 0; i < this->robot_state_.cartesian_contact.size(); i++) {
696  // Evaluate the cartesian contacts/collisions in K frame
697  double fi = std::abs(f_ext_k(i));
699  static_cast<double>(fi > this->lower_force_thresholds_nominal_.at(i));
701  static_cast<double>(fi > this->upper_force_thresholds_nominal_.at(i));
702  }
703 
705  this->robot_state_.time = franka::Duration(time.toNSec() / 1e6 /*ms*/);
707 #ifdef ENABLE_BASE_ACCELERATION
708  // This will always be {0,0,-9.81} on the real robot as it cannot be mounted differently for now
709  this->robot_state_.O_ddP_O = this->gravity_earth_;
710 #endif
711 
712  std_msgs::Bool msg;
713  msg.data = static_cast<decltype(msg.data)>(true);
714  this->robot_initialized_ = true;
715  this->robot_initialized_pub_.publish(msg);
716 }
717 
719  const std::list<hardware_interface::ControllerInfo>& start_list,
720  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/) {
721  return std::all_of(start_list.cbegin(), start_list.cend(), [this](const auto& controller) {
722  return verifier_->isValidController(controller);
723  });
724 }
725 
726 void FrankaHWSim::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
727  const std::list<hardware_interface::ControllerInfo>& stop_list) {
728  forControlledJoint(stop_list, [](franka_gazebo::Joint& joint, const ControlMethod& /*method*/) {
729  joint.control_method = boost::none;
730  joint.stop_position = joint.position;
731  joint.desired_position = joint.position;
732  joint.desired_velocity = 0;
733  });
734  forControlledJoint(start_list, [](franka_gazebo::Joint& joint, const ControlMethod& method) {
735  joint.control_method = method;
736  // sets the desired joint position once for the effort interface
737  joint.desired_position = joint.position;
738  joint.desired_velocity = 0;
739  });
740 
741  this->sm_.process_event(SwitchControl());
742 }
743 
745  const std::list<hardware_interface::ControllerInfo>& controllers,
746  const std::function<void(franka_gazebo::Joint& joint, const ControlMethod&)>& f) {
747  for (const auto& controller : controllers) {
748  if (not verifier_->isClaimingArmController(controller)) {
749  continue;
750  }
751  for (const auto& resource : controller.claimed_resources) {
752  auto control_method = ControllerVerifier::determineControlMethod(resource.hardware_interface);
753  if (not control_method) {
754  continue;
755  }
756  for (const auto& joint_name : resource.resources) {
757  auto& joint = joints_.at(joint_name);
758  f(*joint, control_method.value());
759  }
760  }
761  }
762 }
763 
764 } // namespace franka_gazebo
765 
static boost::optional< ControlMethod > determineControlMethod(const std::string &hardware_interface)
returns the control method of a hardware interface
int type
The type of joint, i.e.
Definition: joint.h:45
std::array< double, 16 > F_T_EE
std::vector< double > lower_force_thresholds_nominal_
void writeSim(ros::Time time, ros::Duration period) override
Pass the data send from controllers via the hardware interfaces onto the simulation.
bool robot_initialized_
If gazebo::Joint::GetForceTorque() yielded already a non-zero value.
std::array< double, 7 > dtau_J
joint_limits_interface::JointLimits limits
Joint limits.
Definition: joint.h:49
std::vector< double > upper_force_thresholds_nominal_
std::array< double, 7 > tau_ext_hat_filtered
#define ROS_FATAL(...)
#define ROS_INFO_NAMED(name,...)
void pseudoInverse(const Eigen::MatrixXd &M_, Eigen::MatrixXd &M_pinv_, bool damped=true)
std::array< double, 3 > F_x_Cload
#define ROS_DEBUG_STREAM_NAMED(name, args)
control_toolbox::Pid velocity_controller
The PID gains used for the controller, when in "velocity" control mode.
Definition: joint.h:168
#define ROS_ERROR_STREAM_NAMED(name, args)
double desired_position
The current desired position that is used for the PID controller when the joints control method is "P...
Definition: joint.h:62
f
franka_hw::FrankaModelInterface fmi_
void initPositionCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
void eStopActive(const bool active) override
Set the emergency stop state (not yet implemented)
hardware_interface::VelocityJointInterface vji_
uint64_t toNSec() const
std::unique_ptr< ControllerVerifier > verifier_
goal
double velocity
The current velocity of this joint either in or .
Definition: joint.h:80
ros::ServiceServer service_collision_behavior_
double stop_position
Position used as desired position if control_method is none.
Definition: joint.h:101
bool call(MReq &req, MRes &res)
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > action_recovery_
std::vector< std::string > getNames() const
#define ROS_INFO_STREAM_NAMED(name, args)
std::array< double, 7 > q_d
ControlMethod
Specifies the current control method of the joint.
Definition: joint.h:17
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::array< double, 6 > K_F_ext_hat_K
std::array< double, 6 > O_F_ext_hat_K
hardware_interface::JointStateInterface jsi_
ros::ServiceServer service_set_ee_
franka_hw::FrankaStateInterface fsi_
void guessEndEffector(const ros::NodeHandle &nh, const urdf::Model &urdf)
std::array< double, 3 > F_x_Cee
std::array< double, 7 > joint_contact
franka::RobotState robot_state_
ros::ServiceClient service_controller_list_
gazebo::physics::ModelPtr robot_
std::array< double, 7 > q
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
Switches the control mode of the robot arm.
A custom implementation of a gazebo_ros_control plugin, which is able to simulate franka interfaces i...
Definition: franka_hw_sim.h:50
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
name
std::array< double, 7 > dtheta
ros::ServiceServer service_set_k_
PLUGINLIB_EXPORT_CLASS(franka_gazebo::FrankaGripperSim, controller_interface::ControllerBase)
A data container holding all relevant information about a robotic joint.
Definition: joint.h:25
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
bool initSim(const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent, const urdf::Model *const urdf, std::vector< transmission_interface::TransmissionInfo > transmissions) override
Initialize the simulated robot hardware and parse all supported transmissions.
void readSim(ros::Time time, ros::Duration period) override
Fetch data from the Gazebo simulation and pass it on to the hardware interfaces.
double computeCommand(double error, ros::Duration dt)
def error(args, kwargs)
bool getParam(const std::string &key, std::string &s) const
boost::sml::sm< franka_gazebo::StateMachine, boost::sml::thread_safe< std::mutex > > sm_
std::array< double, 7 > dq
void initJointStateHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
ros::ServiceServer service_user_stop_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
hardware_interface::PositionJointInterface pji_
std::array< double, 16 > O_T_EE
ros::Publisher robot_initialized_pub_
std::array< double, 9 > I_load
static double positionControl(Joint &joint, double setpoint, const ros::Duration &period)
std::array< double, 7 > dq_d
void registerHandle(const JointStateHandle &handle)
hardware_interface::EffortJointInterface eji_
bool hasParam(const std::string &key) const
control_toolbox::Pid position_controller
The PID gains used for the controller, when in "position" control mode.
Definition: joint.h:164
void initEffortCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
void initServices(ros::NodeHandle &nh)
def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit)
void updateRobotState(ros::Time time)
void initVelocityCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
JointStateHandle getHandle(const std::string &name)
std::array< double, 7 > joint_collision
void initFrankaModelHandle(const std::string &robot, const urdf::Model &urdf, const transmission_interface::TransmissionInfo &transmission, double singularity_threshold)
std::array< double, 7 > ddq_d
std::unique_ptr< franka_hw::ModelBase > model_
std::array< double, 7 > tau_J_d
void forControlledJoint(const std::list< hardware_interface::ControllerInfo > &controllers, const std::function< void(franka_gazebo::Joint &joint, const ControlMethod &)> &f)
double position
The current position of this joint either in or .
Definition: joint.h:77
static std::vector< double > getCollisionThresholds(const std::string &name, const ros::NodeHandle &robot_hw_nh, const std::vector< double > &defaults)
FrankaHWSim()
Create a new FrankaHWSim instance.
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
static double velocityControl(Joint &joint, double setpoint, const ros::Duration &period)
bool readParameters(const ros::NodeHandle &nh, const urdf::Model &urdf)
std::array< double, 9 > I_total
ros::ServiceServer service_set_load_
std::array< double, 6 > cartesian_contact
RobotMode robot_mode
std::string getService()
static Eigen::Matrix3d shiftInertiaTensor(Eigen::Matrix3d I, double m, Eigen::Vector3d p)
Shift the moment of inertia tensor by a given offset.
std::array< double, 3 > gravity_earth_
const double kDefaultTauExtLowpassFilter
Definition: franka_hw_sim.h:30
std::array< double, 9 > I_ee
std::map< std::string, std::shared_ptr< franka_gazebo::Joint > > joints_
void initFrankaStateHandle(const std::string &robot, const urdf::Model &urdf, const transmission_interface::TransmissionInfo &transmission)
double control_command_success_rate
std::array< double, 7 > tau_J
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &) override
Check (in non-realtime) if given controllers could be started and stopped from the current state of t...
double desired_velocity
The current desired velocity that is used for the PID controller when the joints control method is "V...
Definition: joint.h:67
boost::optional< ControlMethod > control_method
Decides whether the joint is doing torque control or if the position or velocity should be controlled...
Definition: joint.h:71
std::array< double, 16 > EE_T_K
const std::string response
std::array< double, 6 > cartesian_collision
std::array< double, 7 > theta
ros::ServiceClient service_controller_switch_
#define ROS_WARN_STREAM_NAMED(name, args)


franka_gazebo
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 03:06:05