Classes | Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
franka_hw::FrankaHW Class Reference

This class wraps the functionality of libfranka for controlling Panda robots into the ros_control framework. More...

#include <franka_hw.h>

Inheritance diagram for franka_hw::FrankaHW:
Inheritance graph
[legend]

Classes

struct  CollisionConfig
 

Public Member Functions

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. More...
 
virtual void checkJointLimits ()
 Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint is close to a limit. More...
 
virtual void connect ()
 Create a libfranka robot, connecting the hardware class to the master controller. More...
 
virtual bool connected ()
 Checks whether the hardware class is connected to a robot. More...
 
virtual void control (const std::function< bool(const ros::Time &, const ros::Duration &)> &ros_callback)
 Runs the currently active controller in a realtime loop. More...
 
virtual bool controllerActive () const noexcept
 Indicates whether there is an active controller. More...
 
virtual bool disconnect ()
 Tries to disconnect the hardware class from the robot, freeing it for e.g. More...
 
virtual void doSwitch (const std::list< hardware_interface::ControllerInfo > &, const std::list< hardware_interface::ControllerInfo > &) override
 Performs controller switching (real-time capable). More...
 
virtual void enforceLimits (const ros::Duration &period)
 Enforces limits on position, velocity, and torque level. More...
 
 FrankaHW ()
 Default constructor. More...
 
virtual std::array< double, 7 > getJointEffortCommand () const noexcept
 Gets the current joint torque command. More...
 
virtual std::array< double, 7 > getJointPositionCommand () const noexcept
 Gets the current joint position command. More...
 
virtual std::array< double, 7 > getJointVelocityCommand () const noexcept
 Gets the current joint velocity command. More...
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
 Initializes the FrankaHW class to be fully operational. More...
 
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. More...
 
virtual void initROSInterfaces (ros::NodeHandle &robot_hw_nh)
 Initializes the class in terms of ros_control interfaces. More...
 
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). More...
 
virtual void read (const ros::Time &time, const ros::Duration &period) override
 Reads data from the franka robot. More...
 
virtual void reset ()
 Resets the limit interfaces. More...
 
virtual franka::Robot & robot () const
 Getter for the libfranka robot instance. More...
 
virtual std::mutex & robotMutex ()
 Getter for the mutex protecting access to the libfranka::robot class. More...
 
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. More...
 
virtual void update (const franka::RobotState &robot_state)
 Updates the controller interfaces from the given robot state. More...
 
virtual void write (const ros::Time &time, const ros::Duration &period) override
 Writes data to the franka robot. More...
 
virtual ~FrankaHW () override=default
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual SwitchState switchResult () const
 
virtual SwitchState switchResult (const ControllerInfo &) const
 
virtual ~RobotHW ()=default
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Static Public Member Functions

static bool commandHasNaN (const franka::CartesianPose &command)
 Checks a command for NaN values. More...
 
static bool commandHasNaN (const franka::CartesianVelocities &command)
 Checks a command for NaN values. More...
 
static bool commandHasNaN (const franka::JointPositions &command)
 Checks a command for NaN values. More...
 
static bool commandHasNaN (const franka::JointVelocities &command)
 Checks a command for NaN values. More...
 
static bool commandHasNaN (const franka::Torques &command)
 Checks a command for NaN values. More...
 
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. More...
 

Protected Types

using Callback = std::function< bool(const franka::RobotState &, franka::Duration)>
 
- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 

Protected Member Functions

template<typename T >
controlCallback (const T &command, Callback ros_callback, const franka::RobotState &robot_state, franka::Duration time_step)
 Callback for the libfranka control loop. More...
 
virtual void initRobot ()
 Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model. More...
 
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 control mode. More...
 
virtual void setupFrankaCartesianPoseInterface (franka::CartesianPose &pose_cartesian_command)
 Configures and registers the command interface for Cartesian poses in ros_control. More...
 
virtual void setupFrankaCartesianVelocityInterface (franka::CartesianVelocities &velocity_cartesian_command)
 Configures and registers the command interface for Cartesian velocities in ros_control. More...
 
virtual void setupFrankaModelInterface (franka::RobotState &robot_state)
 Configures and registers the model interface offering kinematics and dynamics in ros_control. More...
 
virtual void setupFrankaStateInterface (franka::RobotState &robot_state)
 Configures and registers the state interface offering the full franka::RobotState in ros_control. More...
 
template<typename T >
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. More...
 
virtual void setupJointStateInterface (franka::RobotState &robot_state)
 Configures and registers the joint state interface in ros_control. More...
 
template<typename T >
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 commands. More...
 

Static Protected Member Functions

template<size_t size>
static bool arrayHasNaN (const std::array< double, size > &array)
 Checks whether an array of doubles contains NaN values. More...
 

Protected Attributes

std::string arm_id_
 
CollisionConfig collision_config_
 
std::atomic_bool controller_active_ {false}
 
ControlMode current_control_mode_ = ControlMode::None
 
franka::Torques effort_joint_command_libfranka_
 
franka::Torques effort_joint_command_ros_
 
hardware_interface::EffortJointInterface effort_joint_interface_ {}
 
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_ {}
 
FrankaModelInterface franka_model_interface_ {}
 
FrankaPoseCartesianInterface franka_pose_cartesian_interface_ {}
 
FrankaStateInterface franka_state_interface_ {}
 
FrankaVelocityCartesianInterface franka_velocity_cartesian_interface_ {}
 
std::function< double()> get_cutoff_frequency_
 
std::function< franka::ControllerMode()> get_internal_controller_
 
std::function< bool()> get_limit_rate_
 
bool initialized_ {false}
 
double joint_limit_warning_threshold_ {0.1}
 
std::array< std::string, 7 > joint_names_
 
hardware_interface::JointStateInterface joint_state_interface_ {}
 
std::mutex libfranka_cmd_mutex_
 
std::mutex libfranka_state_mutex_
 
std::unique_ptr< franka_hw::ModelBasemodel_
 
franka::CartesianPose pose_cartesian_command_libfranka_
 
franka::CartesianPose pose_cartesian_command_ros_
 
franka::JointPositions position_joint_command_libfranka_
 
franka::JointPositions position_joint_command_ros_
 
hardware_interface::PositionJointInterface position_joint_interface_ {}
 
joint_limits_interface::PositionJointSoftLimitsInterface position_joint_limit_interface_ {}
 
franka::RealtimeConfig realtime_config_
 
std::unique_ptr< franka::Robot > robot_
 
std::string robot_ip_
 
std::mutex robot_mutex_
 
franka::RobotState robot_state_libfranka_ {}
 
franka::RobotState robot_state_ros_ {}
 
std::mutex ros_cmd_mutex_
 
std::mutex ros_state_mutex_
 
std::function< void(franka::Robot &, Callback)> run_function_
 
urdf::Model urdf_model_
 
franka::CartesianVelocities velocity_cartesian_command_libfranka_
 
franka::CartesianVelocities velocity_cartesian_command_ros_
 
franka::JointVelocities velocity_joint_command_libfranka_
 
franka::JointVelocities velocity_joint_command_ros_
 
hardware_interface::VelocityJointInterface velocity_joint_interface_ {}
 
joint_limits_interface::VelocityJointSoftLimitsInterface velocity_joint_limit_interface_ {}
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
std::vector< ResourceManagerBase * > interface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR }
 

Detailed Description

This class wraps the functionality of libfranka for controlling Panda robots into the ros_control framework.

Definition at line 38 of file franka_hw.h.

Member Typedef Documentation

◆ Callback

using franka_hw::FrankaHW::Callback = std::function<bool(const franka::RobotState&, franka::Duration)>
protected

Definition at line 311 of file franka_hw.h.

Constructor & Destructor Documentation

◆ FrankaHW()

franka_hw::FrankaHW::FrankaHW ( )

Default constructor.

Note: Be sure to call the init() method before operation.

Definition at line 45 of file franka_hw.cpp.

◆ ~FrankaHW()

virtual franka_hw::FrankaHW::~FrankaHW ( )
overridevirtualdefault

Member Function Documentation

◆ arrayHasNaN()

template<size_t size>
static bool franka_hw::FrankaHW::arrayHasNaN ( const std::array< double, size > &  array)
inlinestaticprotected

Checks whether an array of doubles contains NaN values.

Parameters
[in]commandarray The array to check.
Returns
True if the array contains NaN values, false otherwise.

Definition at line 307 of file franka_hw.h.

◆ checkForConflict()

bool franka_hw::FrankaHW::checkForConflict ( const std::list< hardware_interface::ControllerInfo > &  info) const
overridevirtual

Checks whether a requested controller can be run, based on the resources and interfaces it claims.

Parameters
[in]infoControllers to be running at the same time.
Returns
True in case of a conflict, false in case of valid controllers.

Reimplemented from hardware_interface::RobotHW.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 253 of file franka_hw.cpp.

◆ checkJointLimits()

void franka_hw::FrankaHW::checkJointLimits ( )
virtual

Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint is close to a limit.

Definition at line 334 of file franka_hw.cpp.

◆ commandHasNaN() [1/5]

bool franka_hw::FrankaHW::commandHasNaN ( const franka::CartesianPose &  command)
static

Checks a command for NaN values.

Parameters
[in]commandThe command to check.
Returns
True if the command contains NaN, false otherwise.

Definition at line 593 of file franka_hw.cpp.

◆ commandHasNaN() [2/5]

bool franka_hw::FrankaHW::commandHasNaN ( const franka::CartesianVelocities &  command)
static

Checks a command for NaN values.

Parameters
[in]commandThe command to check.
Returns
True if the command contains NaN, false otherwise.

Definition at line 597 of file franka_hw.cpp.

◆ commandHasNaN() [3/5]

bool franka_hw::FrankaHW::commandHasNaN ( const franka::JointPositions &  command)
static

Checks a command for NaN values.

Parameters
[in]commandThe command to check.
Returns
True if the command contains NaN, false otherwise.

Definition at line 585 of file franka_hw.cpp.

◆ commandHasNaN() [4/5]

bool franka_hw::FrankaHW::commandHasNaN ( const franka::JointVelocities &  command)
static

Checks a command for NaN values.

Parameters
[in]commandThe command to check.
Returns
True if the command contains NaN, false otherwise.

Definition at line 589 of file franka_hw.cpp.

◆ commandHasNaN() [5/5]

bool franka_hw::FrankaHW::commandHasNaN ( const franka::Torques &  command)
static

Checks a command for NaN values.

Parameters
[in]commandThe command to check.
Returns
True if the command contains NaN, false otherwise.

Definition at line 581 of file franka_hw.cpp.

◆ connect()

void franka_hw::FrankaHW::connect ( )
virtual

Create a libfranka robot, connecting the hardware class to the master controller.

Note: While the robot is connected, no DESK based tasks can be executed.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 179 of file franka_hw.cpp.

◆ connected()

bool franka_hw::FrankaHW::connected ( )
virtual

Checks whether the hardware class is connected to a robot.

Returns
true if connected, false otherwise.

Definition at line 204 of file franka_hw.cpp.

◆ control()

void franka_hw::FrankaHW::control ( const std::function< bool(const ros::Time &, const ros::Duration &)> &  ros_callback)
virtual

Runs the currently active controller in a realtime loop.

If no controller is active, the function immediately exits. When running a controller, the function only exits when ros_callback returns false.

Parameters
[in]ros_callbackA callback function that is executed at each time step and runs all ROS-side functionality of the hardware. Execution is stopped if it returns false.
Exceptions
franka::ControlExceptionif an error related to torque control or motion generation occurred.
franka::InvalidOperationExceptionif a conflicting operation is already running.
franka::NetworkExceptionif the connection is lost, e.g. after a timeout.
franka::RealtimeExceptionif realtime priority cannot be set for the current thread.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 221 of file franka_hw.cpp.

◆ controlCallback()

template<typename T >
T franka_hw::FrankaHW::controlCallback ( const T &  command,
Callback  ros_callback,
const franka::RobotState &  robot_state,
franka::Duration  time_step 
)
inlineprotected

Callback for the libfranka control loop.

This method is designed to incorporate a second callback named ros_callback that will be called on each iteration of the callback.

Parameters
[in]commandThe datafield containing the command to send to the robot.
[in]ros_callbackAn additional callback that is executed every time step.
[in]robot_stateThe current robot state to compute commands with.
[in]time_stepTime since last call to the callback.
Exceptions
std::invalid_argumentWhen a command contains NaN values.
Returns
The command to be sent to the robot via libfranka.

Definition at line 326 of file franka_hw.h.

◆ controllerActive()

bool franka_hw::FrankaHW::controllerActive ( ) const
virtualnoexcept

Indicates whether there is an active controller.

Returns
True if a controller is currently active, false otherwise.

Definition at line 213 of file franka_hw.cpp.

◆ disconnect()

bool franka_hw::FrankaHW::disconnect ( )
virtual

Tries to disconnect the hardware class from the robot, freeing it for e.g.

DESK-based tasks. Note: Disconnecting is only possible when no controller is actively running.

Returns
true if successfully disconnected, false otherwise.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 194 of file franka_hw.cpp.

◆ doSwitch()

void franka_hw::FrankaHW::doSwitch ( const std::list< hardware_interface::ControllerInfo > &  ,
const std::list< hardware_interface::ControllerInfo > &   
)
overridevirtual

Performs controller switching (real-time capable).

Reimplemented from hardware_interface::RobotHW.

Definition at line 268 of file franka_hw.cpp.

◆ enforceLimits()

void franka_hw::FrankaHW::enforceLimits ( const ros::Duration period)
virtual

Enforces limits on position, velocity, and torque level.

Parameters
[in]periodThe duration of the current cycle.

Definition at line 245 of file franka_hw.cpp.

◆ getCollisionThresholds()

std::vector< double > franka_hw::FrankaHW::getCollisionThresholds ( const std::string &  name,
const ros::NodeHandle robot_hw_nh,
const std::vector< double > &  defaults 
)
static

Parses a set of collision thresholds from the parameter server.

The methods returns the default values if no parameter was found or the size of the array did not match the defaults dimension.

Parameters
[in]nameThe name of the parameter to look for.
[in]robot_hw_nhA node handle in the namespace of the robot hardware.
[in]defaultsA set of default values that also specify the size the parameter must have to be valid.
Returns
A set parsed parameters if valid parameters where found, the default values otherwise.

Definition at line 601 of file franka_hw.cpp.

◆ getJointEffortCommand()

std::array< double, 7 > franka_hw::FrankaHW::getJointEffortCommand ( ) const
virtualnoexcept

Gets the current joint torque command.

Returns
The current joint torque command.

Definition at line 326 of file franka_hw.cpp.

◆ getJointPositionCommand()

std::array< double, 7 > franka_hw::FrankaHW::getJointPositionCommand ( ) const
virtualnoexcept

Gets the current joint position command.

Returns
The current joint position command.

Definition at line 318 of file franka_hw.cpp.

◆ getJointVelocityCommand()

std::array< double, 7 > franka_hw::FrankaHW::getJointVelocityCommand ( ) const
virtualnoexcept

Gets the current joint velocity command.

Returns
The current joint velocity command.

Definition at line 322 of file franka_hw.cpp.

◆ init()

bool franka_hw::FrankaHW::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
overridevirtual

Initializes the FrankaHW class to be fully operational.

This involves parsing required configurations from the ROS parameter server, connecting to the robot and setting up interfaces for the ros_control framework.

Parameters
[in]root_nhA node handle in the root namespace of the control node.
[in]robot_hw_nhA node handle in the namespace of the robot hardware.
Returns
True if successful, false otherwise.

Reimplemented from hardware_interface::RobotHW.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 59 of file franka_hw.cpp.

◆ initParameters()

bool franka_hw::FrankaHW::initParameters ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
virtual

Reads the parameterization of the hardware class from the ROS parameter server (e.g.

arm_id, robot_ip joint_names etc.)

Parameters
[in]root_nhA node handle in the root namespace of the control node.
[in]robot_hw_nhA node handle in the namespace of the robot hardware.
Returns
True if successful, false otherwise.

Definition at line 82 of file franka_hw.cpp.

◆ initRobot()

void franka_hw::FrankaHW::initRobot ( )
protectedvirtual

Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 546 of file franka_hw.cpp.

◆ initROSInterfaces()

void franka_hw::FrankaHW::initROSInterfaces ( ros::NodeHandle robot_hw_nh)
virtual

Initializes the class in terms of ros_control interfaces.

Note: You have to call initParameters beforehand. Use the complete initialization routine init() method to control robots.

Parameters
[in]robot_hw_nhA node handle in the namespace of the robot hardware.
Returns
True if successful, false otherwise.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 526 of file franka_hw.cpp.

◆ prepareSwitch()

bool franka_hw::FrankaHW::prepareSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
overridevirtual

Prepares switching between controllers (not real-time capable).

Parameters
[in]start_listControllers requested to be started.
[in]stop_listControllers requested to be stopped.
Returns
True if the preparation has been successful, false otherwise.

Reimplemented from hardware_interface::RobotHW.

Definition at line 277 of file franka_hw.cpp.

◆ read()

void franka_hw::FrankaHW::read ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Reads data from the franka robot.

Parameters
[in]timeThe current time.
[in]periodThe time passed since the last call to read.

Reimplemented from hardware_interface::RobotHW.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 379 of file franka_hw.cpp.

◆ reset()

void franka_hw::FrankaHW::reset ( )
virtual

Resets the limit interfaces.

Definition at line 330 of file franka_hw.cpp.

◆ robot()

franka::Robot & franka_hw::FrankaHW::robot ( ) const
virtual

Getter for the libfranka robot instance.

Exceptions
std::logic_errorin case the robot is not connected or the class in not initialized

Definition at line 369 of file franka_hw.cpp.

◆ robotMutex()

std::mutex & franka_hw::FrankaHW::robotMutex ( )
virtual

Getter for the mutex protecting access to the libfranka::robot class.

This enables thread-safe access to robot().

Returns
A reference to the robot mutex.

Definition at line 217 of file franka_hw.cpp.

◆ setRunFunction()

bool franka_hw::FrankaHW::setRunFunction ( const ControlMode requested_control_mode,
bool  limit_rate,
double  cutoff_frequency,
franka::ControllerMode  internal_controller 
)
protectedvirtual

Configures the run function which is used as libfranka control callback based on the requested control mode.

Parameters
[in]requested_control_modeThe control mode to configure (e.g. torque/position/velocity etc.)
[in]limit_rateFlag to enable/disable rate limiting to smoothen the commands.
[in]cutoff_frequencyThe cutoff frequency applied for command smoothing.
[in]internal_controllerThe internal controller to use when using position or velocity modes.
Returns
True if successful, false otherwise.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 435 of file franka_hw.cpp.

◆ setupFrankaCartesianPoseInterface()

void franka_hw::FrankaHW::setupFrankaCartesianPoseInterface ( franka::CartesianPose &  pose_cartesian_command)
protectedvirtual

Configures and registers the command interface for Cartesian poses in ros_control.

Parameters
[in]pose_cartesian_commandThe data field holding the command to execute.

Definition at line 410 of file franka_hw.cpp.

◆ setupFrankaCartesianVelocityInterface()

void franka_hw::FrankaHW::setupFrankaCartesianVelocityInterface ( franka::CartesianVelocities &  velocity_cartesian_command)
protectedvirtual

Configures and registers the command interface for Cartesian velocities in ros_control.

Parameters
[in]velocity_cartesian_commandThe data field holding the command to execute.

Definition at line 418 of file franka_hw.cpp.

◆ setupFrankaModelInterface()

void franka_hw::FrankaHW::setupFrankaModelInterface ( franka::RobotState &  robot_state)
protectedvirtual

Configures and registers the model interface offering kinematics and dynamics in ros_control.

Parameters
[in]robot_stateA reference to the data field storing the current robot state. This state is used to evaluate model qunatities (by default) at the current state.

Definition at line 427 of file franka_hw.cpp.

◆ setupFrankaStateInterface()

void franka_hw::FrankaHW::setupFrankaStateInterface ( franka::RobotState &  robot_state)
protectedvirtual

Configures and registers the state interface offering the full franka::RobotState in ros_control.

Parameters
[in]robot_stateThe data field holding the updated robot state.

Definition at line 404 of file franka_hw.cpp.

◆ setupJointCommandInterface()

template<typename T >
void franka_hw::FrankaHW::setupJointCommandInterface ( std::array< double, 7 > &  command,
franka::RobotState &  state,
bool  use_q_d,
T &  interface 
)
inlineprotected

Configures and registers a joint command interface for positions velocities or efforts in ros_control.

Parameters
[in]commandThe data field holding the command to execute.
[in]stateThe data field holding the updated robot state.
[in]use_q_dFlag to configure using desired values as joint_states.
[out]interfaceThe command interface to configure.

Definition at line 408 of file franka_hw.h.

◆ setupJointStateInterface()

void franka_hw::FrankaHW::setupJointStateInterface ( franka::RobotState &  robot_state)
protectedvirtual

Configures and registers the joint state interface in ros_control.

Parameters
[in]robot_stateThe data field holding the updated robot state.

Definition at line 395 of file franka_hw.cpp.

◆ setupLimitInterface()

template<typename T >
void franka_hw::FrankaHW::setupLimitInterface ( joint_limits_interface::JointLimitsInterface< T > &  limit_interface,
hardware_interface::JointCommandInterface command_interface 
)
inlineprotected

Configures a limit interface to enforce limits on effort, velocity or position level on joint commands.

Parameters
[out]limit_interfaceThe limit interface to set up.
[out]command_interfaceThe command interface to hook the limit interface to.

Definition at line 356 of file franka_hw.h.

◆ setupParameterCallbacks()

void franka_hw::FrankaHW::setupParameterCallbacks ( ros::NodeHandle robot_hw_nh)
virtual

Initializes the callbacks for on-the-fly reading the parameters for rate limiting, internal controllers and cutoff frequency.

Parameters
[in]robot_hw_nhA node handle in the namespace of the robot hardware.

Definition at line 552 of file franka_hw.cpp.

◆ update()

void franka_hw::FrankaHW::update ( const franka::RobotState &  robot_state)
virtual

Updates the controller interfaces from the given robot state.

Parameters
[in]robot_stateCurrent robot state.

Definition at line 208 of file franka_hw.cpp.

◆ write()

void franka_hw::FrankaHW::write ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Writes data to the franka robot.

Parameters
[in]timeThe current time.
[in]periodThe time passed since the last call to write.

Reimplemented from hardware_interface::RobotHW.

Reimplemented in franka_hw::FrankaCombinableHW.

Definition at line 385 of file franka_hw.cpp.

Member Data Documentation

◆ arm_id_

std::string franka_hw::FrankaHW::arm_id_
protected

Definition at line 528 of file franka_hw.h.

◆ collision_config_

CollisionConfig franka_hw::FrankaHW::collision_config_
protected

Definition at line 491 of file franka_hw.h.

◆ controller_active_

std::atomic_bool franka_hw::FrankaHW::controller_active_ {false}
protected

Definition at line 535 of file franka_hw.h.

◆ current_control_mode_

ControlMode franka_hw::FrankaHW::current_control_mode_ = ControlMode::None
protected

Definition at line 536 of file franka_hw.h.

◆ effort_joint_command_libfranka_

franka::Torques franka_hw::FrankaHW::effort_joint_command_libfranka_
protected

Definition at line 512 of file franka_hw.h.

◆ effort_joint_command_ros_

franka::Torques franka_hw::FrankaHW::effort_joint_command_ros_
protected

Definition at line 519 of file franka_hw.h.

◆ effort_joint_interface_

hardware_interface::EffortJointInterface franka_hw::FrankaHW::effort_joint_interface_ {}
protected

Definition at line 496 of file franka_hw.h.

◆ effort_joint_limit_interface_

joint_limits_interface::EffortJointSoftLimitsInterface franka_hw::FrankaHW::effort_joint_limit_interface_ {}
protected

Definition at line 502 of file franka_hw.h.

◆ franka_model_interface_

FrankaModelInterface franka_hw::FrankaHW::franka_model_interface_ {}
protected

Definition at line 499 of file franka_hw.h.

◆ franka_pose_cartesian_interface_

FrankaPoseCartesianInterface franka_hw::FrankaHW::franka_pose_cartesian_interface_ {}
protected

Definition at line 497 of file franka_hw.h.

◆ franka_state_interface_

FrankaStateInterface franka_hw::FrankaHW::franka_state_interface_ {}
protected

Definition at line 493 of file franka_hw.h.

◆ franka_velocity_cartesian_interface_

FrankaVelocityCartesianInterface franka_hw::FrankaHW::franka_velocity_cartesian_interface_ {}
protected

Definition at line 498 of file franka_hw.h.

◆ get_cutoff_frequency_

std::function<double()> franka_hw::FrankaHW::get_cutoff_frequency_
protected

Definition at line 540 of file franka_hw.h.

◆ get_internal_controller_

std::function<franka::ControllerMode()> franka_hw::FrankaHW::get_internal_controller_
protected

Definition at line 538 of file franka_hw.h.

◆ get_limit_rate_

std::function<bool()> franka_hw::FrankaHW::get_limit_rate_
protected

Definition at line 539 of file franka_hw.h.

◆ initialized_

bool franka_hw::FrankaHW::initialized_ {false}
protected

Definition at line 534 of file franka_hw.h.

◆ joint_limit_warning_threshold_

double franka_hw::FrankaHW::joint_limit_warning_threshold_ {0.1}
protected

Definition at line 531 of file franka_hw.h.

◆ joint_names_

std::array<std::string, 7> franka_hw::FrankaHW::joint_names_
protected

Definition at line 527 of file franka_hw.h.

◆ joint_state_interface_

hardware_interface::JointStateInterface franka_hw::FrankaHW::joint_state_interface_ {}
protected

Definition at line 492 of file franka_hw.h.

◆ libfranka_cmd_mutex_

std::mutex franka_hw::FrankaHW::libfranka_cmd_mutex_
protected

Definition at line 509 of file franka_hw.h.

◆ libfranka_state_mutex_

std::mutex franka_hw::FrankaHW::libfranka_state_mutex_
protected

Definition at line 504 of file franka_hw.h.

◆ model_

std::unique_ptr<franka_hw::ModelBase> franka_hw::FrankaHW::model_
protected

Definition at line 525 of file franka_hw.h.

◆ pose_cartesian_command_libfranka_

franka::CartesianPose franka_hw::FrankaHW::pose_cartesian_command_libfranka_
protected

Definition at line 513 of file franka_hw.h.

◆ pose_cartesian_command_ros_

franka::CartesianPose franka_hw::FrankaHW::pose_cartesian_command_ros_
protected

Definition at line 520 of file franka_hw.h.

◆ position_joint_command_libfranka_

franka::JointPositions franka_hw::FrankaHW::position_joint_command_libfranka_
protected

Definition at line 510 of file franka_hw.h.

◆ position_joint_command_ros_

franka::JointPositions franka_hw::FrankaHW::position_joint_command_ros_
protected

Definition at line 517 of file franka_hw.h.

◆ position_joint_interface_

hardware_interface::PositionJointInterface franka_hw::FrankaHW::position_joint_interface_ {}
protected

Definition at line 494 of file franka_hw.h.

◆ position_joint_limit_interface_

joint_limits_interface::PositionJointSoftLimitsInterface franka_hw::FrankaHW::position_joint_limit_interface_ {}
protected

Definition at line 500 of file franka_hw.h.

◆ realtime_config_

franka::RealtimeConfig franka_hw::FrankaHW::realtime_config_
protected

Definition at line 532 of file franka_hw.h.

◆ robot_

std::unique_ptr<franka::Robot> franka_hw::FrankaHW::robot_
protected

Definition at line 524 of file franka_hw.h.

◆ robot_ip_

std::string franka_hw::FrankaHW::robot_ip_
protected

Definition at line 529 of file franka_hw.h.

◆ robot_mutex_

std::mutex franka_hw::FrankaHW::robot_mutex_
protected

Definition at line 523 of file franka_hw.h.

◆ robot_state_libfranka_

franka::RobotState franka_hw::FrankaHW::robot_state_libfranka_ {}
protected

Definition at line 506 of file franka_hw.h.

◆ robot_state_ros_

franka::RobotState franka_hw::FrankaHW::robot_state_ros_ {}
protected

Definition at line 507 of file franka_hw.h.

◆ ros_cmd_mutex_

std::mutex franka_hw::FrankaHW::ros_cmd_mutex_
protected

Definition at line 516 of file franka_hw.h.

◆ ros_state_mutex_

std::mutex franka_hw::FrankaHW::ros_state_mutex_
protected

Definition at line 505 of file franka_hw.h.

◆ run_function_

std::function<void(franka::Robot&, Callback)> franka_hw::FrankaHW::run_function_
protected

Definition at line 541 of file franka_hw.h.

◆ urdf_model_

urdf::Model franka_hw::FrankaHW::urdf_model_
protected

Definition at line 530 of file franka_hw.h.

◆ velocity_cartesian_command_libfranka_

franka::CartesianVelocities franka_hw::FrankaHW::velocity_cartesian_command_libfranka_
protected

Definition at line 514 of file franka_hw.h.

◆ velocity_cartesian_command_ros_

franka::CartesianVelocities franka_hw::FrankaHW::velocity_cartesian_command_ros_
protected

Definition at line 521 of file franka_hw.h.

◆ velocity_joint_command_libfranka_

franka::JointVelocities franka_hw::FrankaHW::velocity_joint_command_libfranka_
protected

Definition at line 511 of file franka_hw.h.

◆ velocity_joint_command_ros_

franka::JointVelocities franka_hw::FrankaHW::velocity_joint_command_ros_
protected

Definition at line 518 of file franka_hw.h.

◆ velocity_joint_interface_

hardware_interface::VelocityJointInterface franka_hw::FrankaHW::velocity_joint_interface_ {}
protected

Definition at line 495 of file franka_hw.h.

◆ velocity_joint_limit_interface_

joint_limits_interface::VelocityJointSoftLimitsInterface franka_hw::FrankaHW::velocity_joint_limit_interface_ {}
protected

Definition at line 501 of file franka_hw.h.


The documentation for this class was generated from the following files:


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21