Go to the documentation of this file.
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>
131 virtual void update(
const franka::RobotState& robot_state);
149 const std::list<hardware_interface::ControllerInfo>& info)
const override;
155 const std::list<hardware_interface::ControllerInfo>& ,
156 const std::list<hardware_interface::ControllerInfo>& )
override;
167 const std::list<hardware_interface::ControllerInfo>& start_list,
168 const std::list<hardware_interface::ControllerInfo>& stop_list)
override;
201 virtual void reset();
229 virtual franka::Robot&
robot()
const;
296 const std::vector<double>& defaults);
306 template <
size_t size>
308 return std::any_of(array.begin(), array.end(), [](
const double& e) { return std::isnan(e); });
311 using Callback = std::function<bool(
const franka::RobotState&, franka::Duration)>;
325 template <
typename T>
328 const franka::RobotState& robot_state,
329 franka::Duration time_step) {
335 return franka::MotionFinished(
command);
340 std::string error_message =
"FrankaHW::controlCallback: Got NaN command!";
342 throw std::invalid_argument(error_message);
355 template <
typename T>
362 auto urdf_joint =
urdf_model_.getJoint(joint_name);
363 if (!urdf_joint || !urdf_joint->safety || !urdf_joint->limits) {
365 "FrankaHW: Joint %s has incomplete limits and safety specs. Skipping it in the joint "
374 joint_limits.
max_jerk = franka::kMaxJointJerk[i];
376 T limit_handle(command_interface.
getHandle(joint_name), joint_limits, soft_limits);
377 limit_interface.registerHandle(limit_handle);
380 "FrankaHW: Could not parse joint limit for joint: %s for joint limit interfaces",
385 "FrankaHW: Could not parse soft joint limit for joint %s for joint limit interfaces",
407 template <
typename T>
409 franka::RobotState& state,
416 &state.dq_d[i], &state.tau_J[i]);
419 &state.dq[i], &state.tau_J[i]);
422 interface.registerHandle(joint_handle);
448 franka::CartesianVelocities& velocity_cartesian_command);
473 double cutoff_frequency,
474 franka::ControllerMode internal_controller);
525 std::unique_ptr<franka_hw::ModelBase>
model_;
virtual std::mutex & robotMutex()
Getter for the mutex protecting access to the libfranka::robot class.
std::mutex libfranka_state_mutex_
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 setupFrankaCartesianVelocityInterface(franka::CartesianVelocities &velocity_cartesian_command)
Configures and registers the command interface for Cartesian velocities in ros_control.
FrankaStateInterface franka_state_interface_
virtual void initROSInterfaces(ros::NodeHandle &robot_hw_nh)
Initializes the class in terms of ros_control interfaces.
hardware_interface::VelocityJointInterface velocity_joint_interface_
FrankaPoseCartesianInterface franka_pose_cartesian_interface_
std::array< double, 6 > upper_force_thresholds_nominal
virtual void setupFrankaCartesianPoseInterface(franka::CartesianPose &pose_cartesian_command)
Configures and registers the command interface for Cartesian poses in ros_control.
This class wraps the functionality of libfranka for controlling Panda robots into the ros_control fra...
JointHandle getHandle(const std::string &name)
franka::JointPositions position_joint_command_libfranka_
std::function< bool()> get_limit_rate_
void registerInterface(T *iface)
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...
virtual void setupParameterCallbacks(ros::NodeHandle &robot_hw_nh)
Initializes the callbacks for on-the-fly reading the parameters for rate limiting,...
ROSLIB_DECL std::string command(const std::string &cmd)
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, JointLimits &limits)
virtual void setupFrankaModelInterface(franka::RobotState &robot_state)
Configures and registers the model interface offering kinematics and dynamics in ros_control.
virtual bool controllerActive() const noexcept
Indicates whether there is an active controller.
virtual std::array< double, 7 > getJointPositionCommand() const noexcept
Gets the current joint position command.
std::unique_ptr< franka_hw::ModelBase > model_
franka::JointVelocities velocity_joint_command_ros_
std::mutex ros_cmd_mutex_
franka::JointPositions position_joint_command_ros_
virtual void write(const ros::Time &time, const ros::Duration &period) override
Writes data to the franka robot.
std::array< double, 7 > upper_torque_thresholds_nominal
franka::CartesianVelocities velocity_cartesian_command_ros_
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.
franka::CartesianVelocities velocity_cartesian_command_libfranka_
virtual void setupJointStateInterface(franka::RobotState &robot_state)
Configures and registers the joint state interface in ros_control.
franka::Torques effort_joint_command_ros_
joint_limits_interface::PositionJointSoftLimitsInterface position_joint_limit_interface_
FrankaModelInterface franka_model_interface_
virtual void update(const franka::RobotState &robot_state)
Updates the controller interfaces from the given robot state.
franka::RealtimeConfig realtime_config_
joint_limits_interface::VelocityJointSoftLimitsInterface velocity_joint_limit_interface_
franka::CartesianPose pose_cartesian_command_libfranka_
hardware_interface::EffortJointInterface effort_joint_interface_
std::array< double, 6 > lower_force_thresholds_nominal
std::array< double, 7 > lower_torque_thresholds_nominal
virtual std::array< double, 7 > getJointEffortCommand() const noexcept
Gets the current joint torque command.
virtual void initRobot()
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
std::function< void(franka::Robot &, Callback)> run_function_
virtual void connect()
Create a libfranka robot, connecting the hardware class to the master controller.
virtual ~FrankaHW() override=default
franka::Torques effort_joint_command_libfranka_
std::function< double()> get_cutoff_frequency_
franka::JointVelocities velocity_joint_command_libfranka_
std::array< double, 7 > upper_torque_thresholds_acceleration
virtual void checkJointLimits()
Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint...
Hardware interface to command Cartesian velocities.
Hardware interface to command Cartesian poses.
std::mutex libfranka_cmd_mutex_
hardware_interface::PositionJointInterface position_joint_interface_
ControlMode current_control_mode_
std::array< double, 6 > lower_force_thresholds_acceleration
Hardware interface to read the complete robot state.
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....
franka::RobotState robot_state_ros_
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.
FrankaHW()
Default constructor.
virtual bool connected()
Checks whether the hardware class is connected to a robot.
std::unique_ptr< franka::Robot > robot_
virtual void control(const std::function< bool(const ros::Time &, const ros::Duration &)> &ros_callback)
Runs the currently active controller in a realtime loop.
std::array< std::string, 7 > joint_names_
std::array< double, 6 > upper_force_thresholds_acceleration
virtual bool disconnect()
Tries to disconnect the hardware class from the robot, freeing it for e.g.
virtual void enforceLimits(const ros::Duration &period)
Enforces limits on position, velocity, and torque level.
CollisionConfig collision_config_
FrankaVelocityCartesianInterface franka_velocity_cartesian_interface_
Hardware interface to perform calculations using the dynamic model of a robot.
franka::RobotState robot_state_libfranka_
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
std::array< double, 7 > lower_torque_thresholds_acceleration
virtual void setupFrankaStateInterface(franka::RobotState &robot_state)
Configures and registers the state interface offering the full franka::RobotState in ros_control.
virtual void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the franka robot.
double joint_limit_warning_threshold_
static bool arrayHasNaN(const std::array< double, size > &array)
Checks whether an array of doubles contains NaN values.
bool has_acceleration_limits
T controlCallback(const T &command, Callback ros_callback, const franka::RobotState &robot_state, franka::Duration time_step)
Callback for the libfranka control loop.
std::function< franka::ControllerMode()> get_internal_controller_
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &, const std::list< hardware_interface::ControllerInfo > &) override
Performs controller switching (real-time capable).
hardware_interface::JointStateInterface joint_state_interface_
franka::CartesianPose pose_cartesian_command_ros_
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::mutex ros_state_mutex_
std::function< bool(const franka::RobotState &, franka::Duration)> Callback
bool getSoftJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, SoftJointLimits &soft_limits)
virtual std::array< double, 7 > getJointVelocityCommand() const noexcept
Gets the current joint velocity command.
virtual franka::Robot & robot() const
Getter for the libfranka robot instance.
virtual void reset()
Resets the limit interfaces.
std::atomic_bool controller_active_
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_
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).
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.
franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21