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/rate_limiting.h>
15 #include <franka/robot.h>
16 #include <franka/robot_state.h>
22 #include <ros/time.h>
23 #include <urdf/model.h>
24 
25 #include <franka_hw/control_mode.h>
29 #include <franka_hw/model_base.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 
93  virtual void connect();
94 
100  virtual bool disconnect();
101 
106  virtual bool connected();
107 
123  virtual void control(
124  const std::function<bool(const ros::Time&, const ros::Duration&)>& ros_callback);
125 
131  virtual void update(const franka::RobotState& robot_state);
132 
138  virtual bool controllerActive() const noexcept;
139 
148  virtual bool checkForConflict(
149  const std::list<hardware_interface::ControllerInfo>& info) const override;
150 
154  virtual void doSwitch(
155  const std::list<hardware_interface::ControllerInfo>& /*start_list*/,
156  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/) override;
157 
166  virtual bool prepareSwitch(
167  const std::list<hardware_interface::ControllerInfo>& start_list,
168  const std::list<hardware_interface::ControllerInfo>& stop_list) override;
169 
175  virtual std::array<double, 7> getJointPositionCommand() const noexcept;
176 
182  virtual std::array<double, 7> getJointVelocityCommand() const noexcept;
183 
189  virtual std::array<double, 7> getJointEffortCommand() const noexcept;
190 
196  virtual void enforceLimits(const ros::Duration& period);
197 
201  virtual void reset();
202 
207  virtual void checkJointLimits();
208 
215  virtual void read(const ros::Time& time, const ros::Duration& period) override;
216 
223  virtual void write(const ros::Time& time, const ros::Duration& period) override;
224 
229  virtual franka::Robot& robot() const;
230 
236  virtual std::mutex& robotMutex();
237 
245  static bool commandHasNaN(const franka::Torques& command);
246 
254  static bool commandHasNaN(const franka::JointPositions& command);
255 
263  static bool commandHasNaN(const franka::JointVelocities& command);
264 
272  static bool commandHasNaN(const franka::CartesianPose& command);
273 
281  static bool commandHasNaN(const franka::CartesianVelocities& command);
282 
294  static std::vector<double> getCollisionThresholds(const std::string& name,
295  const ros::NodeHandle& robot_hw_nh,
296  const std::vector<double>& defaults);
297 
298  protected:
306  template <size_t size>
307  static bool arrayHasNaN(const std::array<double, size>& array) {
308  return std::any_of(array.begin(), array.end(), [](const double& e) { return std::isnan(e); });
309  }
310 
311  using Callback = std::function<bool(const franka::RobotState&, franka::Duration)>;
312 
325  template <typename T>
326  T controlCallback(const T& command,
327  Callback ros_callback,
328  const franka::RobotState& robot_state,
329  franka::Duration time_step) {
330  robot_state_libfranka_ = robot_state;
331  ros::Time now = ros::Time(0);
332  read(now, ros::Duration(time_step.toSec()));
333 
334  if (!controller_active_ || (ros_callback && !ros_callback(robot_state, time_step))) {
335  return franka::MotionFinished(command);
336  }
337 
338  write(now, ros::Duration(time_step.toSec()));
339  if (commandHasNaN(command)) {
340  std::string error_message = "FrankaHW::controlCallback: Got NaN command!";
341  ROS_FATAL("%s", error_message.c_str());
342  throw std::invalid_argument(error_message);
343  }
344 
345  return command;
346  }
347 
355  template <typename T>
357  hardware_interface::JointCommandInterface& command_interface) {
360  for (size_t i = 0; i < joint_names_.size(); i++) {
361  const std::string& joint_name = joint_names_[i];
362  auto urdf_joint = urdf_model_.getJoint(joint_name);
363  if (!urdf_joint || !urdf_joint->safety || !urdf_joint->limits) {
364  ROS_WARN(
365  "FrankaHW: Joint %s has incomplete limits and safety specs. Skipping it in the joint "
366  "limit interface!",
367  joint_name.c_str());
368  continue;
369  }
370  if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) {
371  if (joint_limits_interface::getJointLimits(urdf_joint, joint_limits)) {
372  joint_limits.max_acceleration = franka::kMaxJointAcceleration[i];
373  joint_limits.has_acceleration_limits = true;
374  joint_limits.max_jerk = franka::kMaxJointJerk[i];
375  joint_limits.has_jerk_limits = true;
376  T limit_handle(command_interface.getHandle(joint_name), joint_limits, soft_limits);
377  limit_interface.registerHandle(limit_handle);
378  } else {
379  ROS_ERROR(
380  "FrankaHW: Could not parse joint limit for joint: %s for joint limit interfaces",
381  joint_name.c_str());
382  }
383  } else {
384  ROS_ERROR(
385  "FrankaHW: Could not parse soft joint limit for joint %s for joint limit interfaces",
386  joint_name.c_str());
387  }
388  }
389  }
390 
396  virtual void setupJointStateInterface(franka::RobotState& robot_state);
397 
407  template <typename T>
408  void setupJointCommandInterface(std::array<double, 7>& command,
409  franka::RobotState& state,
410  bool use_q_d,
411  T& interface) {
412  for (size_t i = 0; i < joint_names_.size(); i++) {
414  if (use_q_d) {
415  state_handle = hardware_interface::JointStateHandle(joint_names_[i], &state.q_d[i],
416  &state.dq_d[i], &state.tau_J[i]);
417  } else {
418  state_handle = hardware_interface::JointStateHandle(joint_names_[i], &state.q[i],
419  &state.dq[i], &state.tau_J[i]);
420  }
421  hardware_interface::JointHandle joint_handle(state_handle, &command[i]);
422  interface.registerHandle(joint_handle);
423  }
424  registerInterface(&interface);
425  }
426 
433  virtual void setupFrankaStateInterface(franka::RobotState& robot_state);
434 
440  virtual void setupFrankaCartesianPoseInterface(franka::CartesianPose& pose_cartesian_command);
441 
448  franka::CartesianVelocities& velocity_cartesian_command);
449 
456  virtual void setupFrankaModelInterface(franka::RobotState& robot_state);
457 
471  virtual bool setRunFunction(const ControlMode& requested_control_mode,
472  bool limit_rate,
473  double cutoff_frequency,
474  franka::ControllerMode internal_controller);
478  virtual void initRobot();
479 
483  std::array<double, 7> lower_torque_thresholds_nominal;
484  std::array<double, 7> upper_torque_thresholds_nominal;
485  std::array<double, 6> lower_force_thresholds_acceleration;
486  std::array<double, 6> upper_force_thresholds_acceleration;
487  std::array<double, 6> lower_force_thresholds_nominal;
488  std::array<double, 6> upper_force_thresholds_nominal;
489  };
490 
503 
505  std::mutex ros_state_mutex_;
506  franka::RobotState robot_state_libfranka_{};
507  franka::RobotState robot_state_ros_{};
508 
510  franka::JointPositions position_joint_command_libfranka_;
511  franka::JointVelocities velocity_joint_command_libfranka_;
513  franka::CartesianPose pose_cartesian_command_libfranka_;
514  franka::CartesianVelocities velocity_cartesian_command_libfranka_;
515 
516  std::mutex ros_cmd_mutex_;
517  franka::JointPositions position_joint_command_ros_;
518  franka::JointVelocities velocity_joint_command_ros_;
519  franka::Torques effort_joint_command_ros_;
520  franka::CartesianPose pose_cartesian_command_ros_;
521  franka::CartesianVelocities velocity_cartesian_command_ros_;
522 
523  std::mutex robot_mutex_;
524  std::unique_ptr<franka::Robot> robot_;
525  std::unique_ptr<franka_hw::ModelBase> model_;
526 
527  std::array<std::string, 7> joint_names_;
528  std::string arm_id_;
529  std::string robot_ip_;
532  franka::RealtimeConfig realtime_config_;
533 
534  bool initialized_{false};
535  std::atomic_bool controller_active_{false};
537 
538  std::function<franka::ControllerMode()> get_internal_controller_;
539  std::function<bool()> get_limit_rate_;
540  std::function<double()> get_cutoff_frequency_;
541  std::function<void(franka::Robot&, Callback)> run_function_;
542 };
543 
544 } // 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
joint_limits_interface::JointLimits::has_jerk_limits
bool has_jerk_limits
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
franka_hw::FrankaHW::franka_pose_cartesian_interface_
FrankaPoseCartesianInterface franka_pose_cartesian_interface_
Definition: franka_hw.h:497
joint_limits_interface::JointLimits::max_jerk
double max_jerk
franka_cartesian_command_interface.h
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
franka_hw::FrankaHW
This class wraps the functionality of libfranka for controlling Panda robots into the ros_control fra...
Definition: franka_hw.h:38
HardwareResourceManager< JointHandle, ClaimResources >::getHandle
JointHandle getHandle(const std::string &name)
hardware_interface::JointStateInterface
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
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)
joint_limits_interface::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.h
time.h
control_mode.h
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
model_base.h
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::VelocityJointSoftLimitsInterface
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
urdf::Model
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_state_interface.h
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
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::~FrankaHW
virtual ~FrankaHW() override=default
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
hardware_interface::JointCommandInterface
hardware_interface::VelocityJointInterface
joint_limits_interface::EffortJointSoftLimitsInterface
franka_model_interface.h
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
joint_command_interface.h
franka_hw::FrankaVelocityCartesianInterface
Hardware interface to command Cartesian velocities.
Definition: franka_cartesian_command_interface.h:126
hardware_interface::RobotHW
franka_hw::FrankaHW::robot_mutex_
std::mutex robot_mutex_
Definition: franka_hw.h:523
franka_hw::FrankaPoseCartesianInterface
Hardware interface to command Cartesian poses.
Definition: franka_cartesian_command_interface.h:68
franka_hw::FrankaHW::libfranka_cmd_mutex_
std::mutex libfranka_cmd_mutex_
Definition: franka_hw.h:509
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
model.h
hardware_interface::JointStateHandle
franka_hw::FrankaHW::CollisionConfig::lower_force_thresholds_acceleration
std::array< double, 6 > lower_force_thresholds_acceleration
Definition: franka_hw.h:485
franka_hw::FrankaStateInterface
Hardware interface to read the complete robot state.
Definition: franka_state_interface.h:52
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
hardware_interface::EffortJointInterface
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
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
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::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
ROS_FATAL
#define ROS_FATAL(...)
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::FrankaModelInterface
Hardware interface to perform calculations using the dynamic model of a robot.
Definition: franka_model_interface.h:280
franka_hw::FrankaHW::robot_state_libfranka_
franka::RobotState robot_state_libfranka_
Definition: franka_hw.h:506
joint_state_interface.h
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
hardware_interface::JointHandle
franka_hw::FrankaHW::CollisionConfig::lower_torque_thresholds_acceleration
std::array< double, 7 > lower_torque_thresholds_acceleration
Definition: franka_hw.h:481
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
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
joint_limits_interface::PositionJointSoftLimitsInterface
joint_limits_interface::JointLimits::has_acceleration_limits
bool has_acceleration_limits
franka_hw::FrankaHW::controlCallback
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:326
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
robot_hw.h
joint_limits_interface::JointLimits::max_acceleration
double max_acceleration
franka_hw::FrankaHW::pose_cartesian_command_ros_
franka::CartesianPose pose_cartesian_command_ros_
Definition: franka_hw.h:520
franka_hw::FrankaHW::setupLimitInterface
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:356
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
hardware_interface::PositionJointInterface
joint_limits_interface::SoftJointLimits
joint_limits_interface::getSoftJointLimits
bool getSoftJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, SoftJointLimits &soft_limits)
franka_hw::FrankaHW::getJointVelocityCommand
virtual std::array< double, 7 > getJointVelocityCommand() const noexcept
Gets the current joint velocity command.
Definition: franka_hw.cpp:322
joint_limits_interface::JointLimitsInterface
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::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::NodeHandle
franka_hw::FrankaHW::CollisionConfig
Definition: franka_hw.h:480
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