franka_hw.h
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 #pragma once
4 
5 #include <array>
6 #include <atomic>
7 #include <exception>
8 #include <functional>
9 #include <list>
10 #include <string>
11 
12 #include <franka/control_types.h>
13 #include <franka/duration.h>
14 #include <franka/model.h>
15 #include <franka/rate_limiting.h>
16 #include <franka/robot.h>
17 #include <franka/robot_state.h>
23 #include <ros/time.h>
24 #include <urdf/model.h>
25 
26 #include <franka_hw/control_mode.h>
31 
32 namespace franka_hw {
33 
39  public:
44  FrankaHW();
45 
46  virtual ~FrankaHW() override = default;
47 
58  virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) override;
59 
69  virtual bool initParameters(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh);
70 
79  virtual void initROSInterfaces(ros::NodeHandle& robot_hw_nh);
80 
87  virtual void setupParameterCallbacks(ros::NodeHandle& robot_hw_nh);
88 
104  virtual void control(
105  const std::function<bool(const ros::Time&, const ros::Duration&)>& ros_callback) const;
106 
112  virtual void update(const franka::RobotState& robot_state);
113 
119  virtual bool controllerActive() const noexcept;
120 
129  virtual bool checkForConflict(
130  const std::list<hardware_interface::ControllerInfo>& info) const override;
131 
135  virtual void doSwitch(
136  const std::list<hardware_interface::ControllerInfo>& /*start_list*/,
137  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/) override;
138 
147  virtual bool prepareSwitch(
148  const std::list<hardware_interface::ControllerInfo>& start_list,
149  const std::list<hardware_interface::ControllerInfo>& stop_list) override;
150 
156  virtual std::array<double, 7> getJointPositionCommand() const noexcept;
157 
163  virtual std::array<double, 7> getJointVelocityCommand() const noexcept;
164 
170  virtual std::array<double, 7> getJointEffortCommand() const noexcept;
171 
177  virtual void enforceLimits(const ros::Duration& period);
178 
182  virtual void reset();
183 
188  virtual void checkJointLimits();
189 
196  virtual void read(const ros::Time& time, const ros::Duration& period) override;
197 
204  virtual void write(const ros::Time& time, const ros::Duration& period) override;
205 
209  virtual franka::Robot& robot() const;
210 
218  static bool commandHasNaN(const franka::Torques& command);
219 
227  static bool commandHasNaN(const franka::JointPositions& command);
228 
236  static bool commandHasNaN(const franka::JointVelocities& command);
237 
245  static bool commandHasNaN(const franka::CartesianPose& command);
246 
254  static bool commandHasNaN(const franka::CartesianVelocities& command);
255 
256  protected:
264  template <size_t size>
265  static bool arrayHasNaN(const std::array<double, size>& array) {
266  return std::any_of(array.begin(), array.end(), [](const double& e) { return std::isnan(e); });
267  }
268 
269  using Callback = std::function<bool(const franka::RobotState&, franka::Duration)>;
270 
283  template <typename T>
284  T controlCallback(const T& command,
285  Callback ros_callback,
286  const franka::RobotState& robot_state,
287  franka::Duration time_step) {
288  robot_state_libfranka_ = robot_state;
289  ros::Time now = ros::Time(0);
290  read(now, ros::Duration(time_step.toSec()));
291 
292  if (!controller_active_ || (ros_callback && !ros_callback(robot_state, time_step))) {
293  return franka::MotionFinished(command);
294  }
295 
296  write(now, ros::Duration(time_step.toSec()));
297  if (commandHasNaN(command)) {
298  std::string error_message = "FrankaHW::controlCallback: Got NaN command!";
299  ROS_FATAL("%s", error_message.c_str());
300  throw std::invalid_argument(error_message);
301  }
302 
303  return command;
304  }
305 
313  template <typename T>
315  hardware_interface::JointCommandInterface& command_interface) {
318  for (size_t i = 0; i < joint_names_.size(); i++) {
319  const std::string& joint_name = joint_names_[i];
320  auto urdf_joint = urdf_model_.getJoint(joint_name);
321  if (!urdf_joint || !urdf_joint->safety || !urdf_joint->limits) {
322  ROS_WARN(
323  "FrankaHW: Joint %s has incomplete limits and safety specs. Skipping it in the joint "
324  "limit interface!",
325  joint_name.c_str());
326  continue;
327  }
328  if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) {
329  if (joint_limits_interface::getJointLimits(urdf_joint, joint_limits)) {
331  joint_limits.has_acceleration_limits = true;
332  joint_limits.max_jerk = franka::kMaxJointJerk[i];
333  joint_limits.has_jerk_limits = true;
334  T limit_handle(command_interface.getHandle(joint_name), joint_limits, soft_limits);
335  limit_interface.registerHandle(limit_handle);
336  } else {
337  ROS_ERROR(
338  "FrankaHW: Could not parse joint limit for joint: %s for joint limit interfaces",
339  joint_name.c_str());
340  }
341  } else {
342  ROS_ERROR(
343  "FrankaHW: Could not parse soft joint limit for joint %s for joint limit interfaces",
344  joint_name.c_str());
345  }
346  }
347  }
348 
354  virtual void setupJointStateInterface(franka::RobotState& robot_state);
355 
365  template <typename T>
366  void setupJointCommandInterface(std::array<double, 7>& command,
367  franka::RobotState& state,
368  bool use_q_d,
369  T& interface) {
370  for (size_t i = 0; i < joint_names_.size(); i++) {
372  if (use_q_d) {
373  state_handle = hardware_interface::JointStateHandle(joint_names_[i], &state.q_d[i],
374  &state.dq_d[i], &state.tau_J[i]);
375  } else {
376  state_handle = hardware_interface::JointStateHandle(joint_names_[i], &state.q[i],
377  &state.dq[i], &state.tau_J[i]);
378  }
379  hardware_interface::JointHandle joint_handle(state_handle, &command[i]);
380  interface.registerHandle(joint_handle);
381  }
382  registerInterface(&interface);
383  }
384 
391  virtual void setupFrankaStateInterface(franka::RobotState& robot_state);
392 
398  virtual void setupFrankaCartesianPoseInterface(franka::CartesianPose& pose_cartesian_command);
399 
406  franka::CartesianVelocities& velocity_cartesian_command);
407 
414  virtual void setupFrankaModelInterface(franka::RobotState& robot_state);
415 
429  virtual bool setRunFunction(const ControlMode& requested_control_mode,
430  bool limit_rate,
431  double cutoff_frequency,
432  franka::ControllerMode internal_controller);
436  virtual void initRobot();
437 
449  static std::vector<double> getCollisionThresholds(const std::string& name,
450  ros::NodeHandle& robot_hw_nh,
451  const std::vector<double>& defaults);
452 
456  std::array<double, 7> lower_torque_thresholds_nominal;
457  std::array<double, 7> upper_torque_thresholds_nominal;
458  std::array<double, 6> lower_force_thresholds_acceleration;
459  std::array<double, 6> upper_force_thresholds_acceleration;
460  std::array<double, 6> lower_force_thresholds_nominal;
461  std::array<double, 6> upper_force_thresholds_nominal;
462  };
463 
476 
478  std::mutex ros_state_mutex_;
481 
488 
489  std::mutex ros_cmd_mutex_;
495 
496  std::unique_ptr<franka::Robot> robot_;
497  std::unique_ptr<franka::Model> model_;
498 
499  std::array<std::string, 7> joint_names_;
500  std::string arm_id_;
501  std::string robot_ip_;
505 
506  bool initialized_{false};
507  std::atomic_bool controller_active_{false};
509 
510  std::function<franka::ControllerMode()> get_internal_controller_;
511  std::function<bool()> get_limit_rate_;
512  std::function<double()> get_cutoff_frequency_;
513  std::function<void(franka::Robot&, Callback)> run_function_;
514 };
515 
516 } // namespace franka_hw
static bool arrayHasNaN(const std::array< double, size > &array)
Checks whether an array of doubles contains NaN values.
Definition: franka_hw.h:265
FrankaStateInterface franka_state_interface_
Definition: franka_hw.h:466
virtual std::array< double, 7 > getJointPositionCommand() const noexcept
Gets the current joint position command.
Definition: franka_hw.cpp:284
virtual void enforceLimits(const ros::Duration &period)
Enforces limits on position, velocity, and torque level.
Definition: franka_hw.cpp:211
virtual void setupFrankaCartesianPoseInterface(franka::CartesianPose &pose_cartesian_command)
Configures and registers the command interface for Cartesian poses in ros_control.
Definition: franka_hw.cpp:374
virtual void setupFrankaModelInterface(franka::RobotState &robot_state)
Configures and registers the model interface offering kinematics and dynamics in ros_control.
Definition: franka_hw.cpp:391
#define ROS_FATAL(...)
virtual void reset()
Resets the limit interfaces.
Definition: franka_hw.cpp:296
std::unique_ptr< franka::Model > model_
Definition: franka_hw.h:497
double toSec() const noexcept
std::array< double, 7 > lower_torque_thresholds_nominal
Definition: franka_hw.h:456
virtual bool controllerActive() const noexcept
Indicates whether there is an active controller.
Definition: franka_hw.cpp:184
franka::CartesianVelocities velocity_cartesian_command_libfranka_
Definition: franka_hw.h:487
virtual void setupFrankaCartesianVelocityInterface(franka::CartesianVelocities &velocity_cartesian_command)
Configures and registers the command interface for Cartesian velocities in ros_control.
Definition: franka_hw.cpp:382
Hardware interface to command Cartesian poses.
std::string robot_ip_
Definition: franka_hw.h:501
franka::CartesianVelocities velocity_cartesian_command_ros_
Definition: franka_hw.h:494
FrankaPoseCartesianInterface franka_pose_cartesian_interface_
Definition: franka_hw.h:470
virtual void update(const franka::RobotState &robot_state)
Updates the controller interfaces from the given robot state.
Definition: franka_hw.cpp:179
franka::Torques effort_joint_command_ros_
Definition: franka_hw.h:492
std::array< double, 7 > lower_torque_thresholds_acceleration
Definition: franka_hw.h:454
franka::JointVelocities velocity_joint_command_libfranka_
Definition: franka_hw.h:484
FrankaVelocityCartesianInterface franka_velocity_cartesian_interface_
Definition: franka_hw.h:471
franka::JointVelocities velocity_joint_command_ros_
Definition: franka_hw.h:491
CollisionConfig collision_config_
Definition: franka_hw.h:464
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:219
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:300
Hardware interface to read the complete robot state.
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:399
constexpr std::array< double, 7 > kMaxJointJerk
std::array< double, 7 > q_d
franka::Torques effort_joint_command_libfranka_
Definition: franka_hw.h:485
virtual void control(const std::function< bool(const ros::Time &, const ros::Duration &)> &ros_callback) const
Runs the currently active controller in a realtime loop.
Definition: franka_hw.cpp:188
franka::JointPositions position_joint_command_libfranka_
Definition: franka_hw.h:483
std::string arm_id_
Definition: franka_hw.h:500
#define ROS_WARN(...)
FrankaHW()
Default constructor.
Definition: franka_hw.cpp:45
franka::RobotState robot_state_ros_
Definition: franka_hw.h:480
std::mutex ros_state_mutex_
Definition: franka_hw.h:478
virtual void write(const ros::Time &time, const ros::Duration &period) override
Writes data to the franka robot.
Definition: franka_hw.cpp:349
std::array< double, 6 > lower_force_thresholds_acceleration
Definition: franka_hw.h:458
franka::JointPositions position_joint_command_ros_
Definition: franka_hw.h:490
std::array< double, 7 > q
virtual void initRobot()
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
Definition: franka_hw.cpp:510
std::mutex libfranka_cmd_mutex_
Definition: franka_hw.h:482
std::unique_ptr< franka::Robot > robot_
Definition: franka_hw.h:496
std::array< double, 7 > upper_torque_thresholds_acceleration
Definition: franka_hw.h:455
ControlMode current_control_mode_
Definition: franka_hw.h:508
std::array< double, 6 > upper_force_thresholds_nominal
Definition: franka_hw.h:461
ROSLIB_DECL std::string command(const std::string &cmd)
bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
franka::RobotState robot_state_libfranka_
Definition: franka_hw.h:479
std::mutex ros_cmd_mutex_
Definition: franka_hw.h:489
hardware_interface::EffortJointInterface effort_joint_interface_
Definition: franka_hw.h:469
std::array< std::string, 7 > joint_names_
Definition: franka_hw.h:499
franka::RealtimeConfig realtime_config_
Definition: franka_hw.h:504
virtual std::array< double, 7 > getJointEffortCommand() const noexcept
Gets the current joint torque command.
Definition: franka_hw.cpp:292
std::array< double, 7 > dq
void setupLimitInterface(joint_limits_interface::JointLimitsInterface< T > &limit_interface, hardware_interface::JointCommandInterface &command_interface)
Configures a limit interface to enforce limits on effort, velocity or position level on joint command...
Definition: franka_hw.h:314
std::atomic_bool controller_active_
Definition: franka_hw.h:507
std::function< double()> get_cutoff_frequency_
Definition: franka_hw.h:512
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.
Definition: franka_hw.cpp:82
std::function< franka::ControllerMode()> get_internal_controller_
Definition: franka_hw.h:510
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.
Definition: franka_hw.cpp:524
virtual ~FrankaHW() override=default
std::array< double, 7 > dq_d
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:366
virtual void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the franka robot.
Definition: franka_hw.cpp:343
hardware_interface::PositionJointInterface position_joint_interface_
Definition: franka_hw.h:467
joint_limits_interface::PositionJointSoftLimitsInterface position_joint_limit_interface_
Definition: franka_hw.h:473
static std::vector< double > getCollisionThresholds(const std::string &name, ros::NodeHandle &robot_hw_nh, const std::vector< double > &defaults)
Parses a set of collision thresholds from the parameter server.
Definition: franka_hw.cpp:573
JointHandle getHandle(const std::string &name)
virtual void setupJointStateInterface(franka::RobotState &robot_state)
Configures and registers the joint state interface in ros_control.
Definition: franka_hw.cpp:359
joint_limits_interface::VelocityJointSoftLimitsInterface velocity_joint_limit_interface_
Definition: franka_hw.h:474
urdf::Model urdf_model_
Definition: franka_hw.h:502
This class wraps the functionality of libfranka for controlling Panda robots into the ros_control fra...
Definition: franka_hw.h:38
virtual franka::Robot & robot() const
Getter for the libfranka robot instance.
Definition: franka_hw.cpp:334
Hardware interface to command Cartesian velocities.
double joint_limit_warning_threshold_
Definition: franka_hw.h:503
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:243
FrankaModelInterface franka_model_interface_
Definition: franka_hw.h:472
std::array< double, 6 > lower_force_thresholds_nominal
Definition: franka_hw.h:460
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
franka::CartesianPose pose_cartesian_command_ros_
Definition: franka_hw.h:493
hardware_interface::VelocityJointInterface velocity_joint_interface_
Definition: franka_hw.h:468
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:368
std::function< void(franka::Robot &, Callback)> run_function_
Definition: franka_hw.h:513
std::array< double, 7 > upper_torque_thresholds_nominal
Definition: franka_hw.h:457
constexpr std::array< double, 7 > kMaxJointAcceleration
hardware_interface::JointStateInterface joint_state_interface_
Definition: franka_hw.h:465
std::array< double, 6 > upper_force_thresholds_acceleration
Definition: franka_hw.h:459
Hardware interface to perform calculations using the dynamic model of a robot.
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::CartesianPose pose_cartesian_command_libfranka_
Definition: franka_hw.h:486
Torques MotionFinished(Torques command) noexcept
T controlCallback(const T &command, Callback ros_callback, const franka::RobotState &robot_state, franka::Duration time_step)
Callback for the libfranka control loop.
Definition: franka_hw.h:284
virtual std::array< double, 7 > getJointVelocityCommand() const noexcept
Gets the current joint velocity command.
Definition: franka_hw.cpp:288
#define ROS_ERROR(...)
std::array< double, 7 > tau_J
virtual void initROSInterfaces(ros::NodeHandle &robot_hw_nh)
Initializes the class in terms of ros_control interfaces.
Definition: franka_hw.cpp:490
std::function< bool(const franka::RobotState &, franka::Duration)> Callback
Definition: franka_hw.h:269
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:234
std::function< bool()> get_limit_rate_
Definition: franka_hw.h:511
std::mutex libfranka_state_mutex_
Definition: franka_hw.h:477
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_
Definition: franka_hw.h:475
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.
Definition: franka_hw.cpp:553


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:05