130 const std::list<hardware_interface::ControllerInfo>& info)
const override;
136 const std::list<hardware_interface::ControllerInfo>& ,
137 const std::list<hardware_interface::ControllerInfo>& )
override;
148 const std::list<hardware_interface::ControllerInfo>& start_list,
149 const std::list<hardware_interface::ControllerInfo>& stop_list)
override;
182 virtual void reset();
264 template <
size_t size>
266 return std::any_of(array.begin(), array.end(), [](
const double& e) {
return std::isnan(e); });
269 using Callback = std::function<bool(const franka::RobotState&, franka::Duration)>;
283 template <
typename T>
298 std::string error_message =
"FrankaHW::controlCallback: Got NaN command!";
300 throw std::invalid_argument(error_message);
313 template <
typename T>
320 auto urdf_joint =
urdf_model_.getJoint(joint_name);
321 if (!urdf_joint || !urdf_joint->safety || !urdf_joint->limits) {
323 "FrankaHW: Joint %s has incomplete limits and safety specs. Skipping it in the joint " 334 T limit_handle(command_interface.
getHandle(joint_name), joint_limits, soft_limits);
335 limit_interface.registerHandle(limit_handle);
338 "FrankaHW: Could not parse joint limit for joint: %s for joint limit interfaces",
343 "FrankaHW: Could not parse soft joint limit for joint %s for joint limit interfaces",
365 template <
typename T>
377 &state.
dq[i], &state.
tau_J[i]);
380 interface.registerHandle(joint_handle);
431 double cutoff_frequency,
451 const std::vector<double>& defaults);
void registerInterface(T *iface)
static bool arrayHasNaN(const std::array< double, size > &array)
Checks whether an array of doubles contains NaN values.
FrankaStateInterface franka_state_interface_
virtual std::array< double, 7 > getJointPositionCommand() const noexcept
Gets the current joint position command.
virtual void enforceLimits(const ros::Duration &period)
Enforces limits on position, velocity, and torque level.
virtual void setupFrankaCartesianPoseInterface(franka::CartesianPose &pose_cartesian_command)
Configures and registers the command interface for Cartesian poses in ros_control.
virtual void setupFrankaModelInterface(franka::RobotState &robot_state)
Configures and registers the model interface offering kinematics and dynamics in ros_control.
virtual void reset()
Resets the limit interfaces.
std::unique_ptr< franka::Model > model_
double toSec() const noexcept
std::array< double, 7 > lower_torque_thresholds_nominal
virtual bool controllerActive() const noexcept
Indicates whether there is an active controller.
franka::CartesianVelocities velocity_cartesian_command_libfranka_
virtual void setupFrankaCartesianVelocityInterface(franka::CartesianVelocities &velocity_cartesian_command)
Configures and registers the command interface for Cartesian velocities in ros_control.
Hardware interface to command Cartesian poses.
franka::CartesianVelocities velocity_cartesian_command_ros_
FrankaPoseCartesianInterface franka_pose_cartesian_interface_
virtual void update(const franka::RobotState &robot_state)
Updates the controller interfaces from the given robot state.
franka::Torques effort_joint_command_ros_
std::array< double, 7 > lower_torque_thresholds_acceleration
franka::JointVelocities velocity_joint_command_libfranka_
FrankaVelocityCartesianInterface franka_velocity_cartesian_interface_
franka::JointVelocities velocity_joint_command_ros_
CollisionConfig collision_config_
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...
virtual void checkJointLimits()
Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint...
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...
constexpr std::array< double, 7 > kMaxJointJerk
std::array< double, 7 > q_d
franka::Torques effort_joint_command_libfranka_
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.
franka::JointPositions position_joint_command_libfranka_
FrankaHW()
Default constructor.
franka::RobotState robot_state_ros_
std::mutex ros_state_mutex_
virtual void write(const ros::Time &time, const ros::Duration &period) override
Writes data to the franka robot.
std::array< double, 6 > lower_force_thresholds_acceleration
franka::JointPositions position_joint_command_ros_
std::array< double, 7 > q
virtual void initRobot()
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
std::mutex libfranka_cmd_mutex_
std::unique_ptr< franka::Robot > robot_
std::array< double, 7 > upper_torque_thresholds_acceleration
ControlMode current_control_mode_
std::array< double, 6 > upper_force_thresholds_nominal
ROSLIB_DECL std::string command(const std::string &cmd)
bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
franka::RobotState robot_state_libfranka_
std::mutex ros_cmd_mutex_
hardware_interface::EffortJointInterface effort_joint_interface_
std::array< std::string, 7 > joint_names_
franka::RealtimeConfig realtime_config_
virtual std::array< double, 7 > getJointEffortCommand() const noexcept
Gets the current joint torque command.
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...
std::atomic_bool controller_active_
std::function< double()> get_cutoff_frequency_
bool has_acceleration_limits
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.
std::function< franka::ControllerMode()> get_internal_controller_
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.
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...
virtual void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the franka robot.
hardware_interface::PositionJointInterface position_joint_interface_
joint_limits_interface::PositionJointSoftLimitsInterface position_joint_limit_interface_
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.
JointHandle getHandle(const std::string &name)
virtual void setupJointStateInterface(franka::RobotState &robot_state)
Configures and registers the joint state interface in ros_control.
joint_limits_interface::VelocityJointSoftLimitsInterface velocity_joint_limit_interface_
This class wraps the functionality of libfranka for controlling Panda robots into the ros_control fra...
virtual franka::Robot & robot() const
Getter for the libfranka robot instance.
Hardware interface to command Cartesian velocities.
double joint_limit_warning_threshold_
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).
FrankaModelInterface franka_model_interface_
std::array< double, 6 > lower_force_thresholds_nominal
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
franka::CartesianPose pose_cartesian_command_ros_
hardware_interface::VelocityJointInterface velocity_joint_interface_
virtual void setupFrankaStateInterface(franka::RobotState &robot_state)
Configures and registers the state interface offering the full franka::RobotState in ros_control...
std::function< void(franka::Robot &, Callback)> run_function_
std::array< double, 7 > upper_torque_thresholds_nominal
constexpr std::array< double, 7 > kMaxJointAcceleration
hardware_interface::JointStateInterface joint_state_interface_
std::array< double, 6 > upper_force_thresholds_acceleration
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.
franka::CartesianPose pose_cartesian_command_libfranka_
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.
virtual std::array< double, 7 > getJointVelocityCommand() const noexcept
Gets the current joint velocity command.
std::array< double, 7 > tau_J
virtual void initROSInterfaces(ros::NodeHandle &robot_hw_nh)
Initializes the class in terms of ros_control interfaces.
std::function< bool(const franka::RobotState &, franka::Duration)> Callback
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &, const std::list< hardware_interface::ControllerInfo > &) override
Performs controller switching (real-time capable).
std::function< bool()> get_limit_rate_
std::mutex libfranka_state_mutex_
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.