Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ros_control_boilerplate::GenericHWInterface Class Referenceabstract

Hardware interface for a robot. More...

#include <generic_hw_interface.h>

Inheritance diagram for ros_control_boilerplate::GenericHWInterface:
Inheritance graph
[legend]

Public Member Functions

virtual bool canSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) const
 Check (in non-realtime) if given controllers could be started and stopped from the current state of the RobotHW with regard to necessary hardware interface switches. Start and stop list are disjoint. This is just a check, the actual switch is done in doSwitch() More...
 
virtual void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 Perform (in non-realtime) all necessary hardware interface switches in order to start and stop the given controllers. Start and stop list are disjoint. The feasability was checked in canSwitch() beforehand. More...
 
virtual void enforceLimits (ros::Duration &period)=0
 
 GenericHWInterface (const ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
 Constructor. More...
 
virtual void init ()
 Initialize the hardware interface. More...
 
std::string printCommandHelper ()
 Helper for debugging a joint's command. More...
 
virtual void printState ()
 Helper for debugging a joint's state. More...
 
std::string printStateHelper ()
 
virtual void read (ros::Duration &elapsed_time)=0
 Read the state from the robot hardware. More...
 
virtual void read (const ros::Time &, const ros::Duration &period) override
 Read the state from the robot hardware. More...
 
virtual void registerJointLimits (const hardware_interface::JointHandle &joint_handle_position, const hardware_interface::JointHandle &joint_handle_velocity, const hardware_interface::JointHandle &joint_handle_effort, std::size_t joint_id)
 Register the limits of the joint specified by joint_id and joint_handle. The limits are retrieved from the urdf_model. More...
 
virtual void reset ()
 Set all members to default values. More...
 
virtual void write (ros::Duration &elapsed_time)=0
 Write the command to the robot hardware. More...
 
virtual void write (const ros::Time &, const ros::Duration &period) override
 Write the command to the robot hardware. More...
 
virtual ~GenericHWInterface ()
 Destructor. More...
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
 RobotHW ()
 
virtual ~RobotHW ()
 
- 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)
 

Protected Member Functions

virtual void loadURDF (const ros::NodeHandle &nh, std::string param_name)
 Get the URDF XML from the parameter server. More...
 

Protected Attributes

joint_limits_interface::EffortJointSaturationInterface eff_jnt_sat_interface_
 
joint_limits_interface::EffortJointSoftLimitsInterface eff_jnt_soft_limits_
 
hardware_interface::EffortJointInterface effort_joint_interface_
 
std::vector< double > joint_effort_
 
std::vector< double > joint_effort_command_
 
std::vector< double > joint_effort_limits_
 
std::vector< std::string > joint_names_
 
std::vector< double > joint_position_
 
std::vector< double > joint_position_command_
 
std::vector< double > joint_position_lower_limits_
 
std::vector< double > joint_position_upper_limits_
 
hardware_interface::JointStateInterface joint_state_interface_
 
std::vector< double > joint_velocity_
 
std::vector< double > joint_velocity_command_
 
std::vector< double > joint_velocity_limits_
 
std::string name_
 
ros::NodeHandle nh_
 
std::size_t num_joints_
 
joint_limits_interface::PositionJointSaturationInterface pos_jnt_sat_interface_
 
joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_soft_limits_
 
hardware_interface::PositionJointInterface position_joint_interface_
 
urdf::Modelurdf_model_
 
bool use_rosparam_joint_limits_
 
bool use_soft_limits_if_available_
 
joint_limits_interface::VelocityJointSaturationInterface vel_jnt_sat_interface_
 
joint_limits_interface::VelocityJointSoftLimitsInterface vel_jnt_soft_limits_
 
hardware_interface::VelocityJointInterface velocity_joint_interface_
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Additional Inherited Members

- 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
 

Detailed Description

Hardware interface for a robot.

Definition at line 64 of file generic_hw_interface.h.

Constructor & Destructor Documentation

ros_control_boilerplate::GenericHWInterface::GenericHWInterface ( const ros::NodeHandle nh,
urdf::Model urdf_model = NULL 
)

Constructor.

Parameters
nh- Node handle for topics.
urdf- optional pointer to a parsed robot model

Definition at line 47 of file generic_hw_interface.cpp.

virtual ros_control_boilerplate::GenericHWInterface::~GenericHWInterface ( )
inlinevirtual

Destructor.

Definition at line 75 of file generic_hw_interface.h.

Member Function Documentation

virtual bool ros_control_boilerplate::GenericHWInterface::canSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
) const
inlinevirtual

Check (in non-realtime) if given controllers could be started and stopped from the current state of the RobotHW with regard to necessary hardware interface switches. Start and stop list are disjoint. This is just a check, the actual switch is done in doSwitch()

Definition at line 121 of file generic_hw_interface.h.

virtual void ros_control_boilerplate::GenericHWInterface::doSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
inlinevirtual

Perform (in non-realtime) all necessary hardware interface switches in order to start and stop the given controllers. Start and stop list are disjoint. The feasability was checked in canSwitch() beforehand.

Reimplemented from hardware_interface::RobotHW.

Definition at line 132 of file generic_hw_interface.h.

virtual void ros_control_boilerplate::GenericHWInterface::enforceLimits ( ros::Duration period)
pure virtual

Enforce limits for all values before writing

Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.

void ros_control_boilerplate::GenericHWInterface::init ( )
virtual

Initialize the hardware interface.

Reimplemented in ros_control_boilerplate::SimHWInterface.

Definition at line 66 of file generic_hw_interface.cpp.

void ros_control_boilerplate::GenericHWInterface::loadURDF ( const ros::NodeHandle nh,
std::string  param_name 
)
protectedvirtual

Get the URDF XML from the parameter server.

Definition at line 304 of file generic_hw_interface.cpp.

std::string ros_control_boilerplate::GenericHWInterface::printCommandHelper ( )

Helper for debugging a joint's command.

Definition at line 290 of file generic_hw_interface.cpp.

void ros_control_boilerplate::GenericHWInterface::printState ( )
virtual

Helper for debugging a joint's state.

Definition at line 268 of file generic_hw_interface.cpp.

std::string ros_control_boilerplate::GenericHWInterface::printStateHelper ( )

Definition at line 276 of file generic_hw_interface.cpp.

virtual void ros_control_boilerplate::GenericHWInterface::read ( ros::Duration elapsed_time)
pure virtual

Read the state from the robot hardware.

Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.

virtual void ros_control_boilerplate::GenericHWInterface::read ( const ros::Time ,
const ros::Duration period 
)
inlineoverridevirtual

Read the state from the robot hardware.

Note
This delegates RobotHW::read() calls to read()
Parameters
timeThe current time, currently unused
periodThe time passed since the last call

Reimplemented from hardware_interface::RobotHW.

Definition at line 90 of file generic_hw_interface.h.

void ros_control_boilerplate::GenericHWInterface::registerJointLimits ( const hardware_interface::JointHandle joint_handle_position,
const hardware_interface::JointHandle joint_handle_velocity,
const hardware_interface::JointHandle joint_handle_effort,
std::size_t  joint_id 
)
virtual

Register the limits of the joint specified by joint_id and joint_handle. The limits are retrieved from the urdf_model.

Returns
the joint's type, lower position limit, upper position limit, and effort limit.

Definition at line 121 of file generic_hw_interface.cpp.

void ros_control_boilerplate::GenericHWInterface::reset ( )
virtual

Set all members to default values.

Definition at line 261 of file generic_hw_interface.cpp.

virtual void ros_control_boilerplate::GenericHWInterface::write ( ros::Duration elapsed_time)
pure virtual

Write the command to the robot hardware.

Implemented in ros_control_boilerplate::SimHWInterface, and rrbot_control::RRBotHWInterface.

virtual void ros_control_boilerplate::GenericHWInterface::write ( const ros::Time ,
const ros::Duration period 
)
inlineoverridevirtual

Write the command to the robot hardware.

Note
This delegates RobotHW::write() calls to write()
Parameters
timeThe current time, currently unused
periodThe time passed since the last call

Reimplemented from hardware_interface::RobotHW.

Definition at line 106 of file generic_hw_interface.h.

Member Data Documentation

joint_limits_interface::EffortJointSaturationInterface ros_control_boilerplate::GenericHWInterface::eff_jnt_sat_interface_
protected

Definition at line 178 of file generic_hw_interface.h.

joint_limits_interface::EffortJointSoftLimitsInterface ros_control_boilerplate::GenericHWInterface::eff_jnt_soft_limits_
protected

Definition at line 183 of file generic_hw_interface.h.

hardware_interface::EffortJointInterface ros_control_boilerplate::GenericHWInterface::effort_joint_interface_
protected

Definition at line 173 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_effort_
protected

Definition at line 197 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_effort_command_
protected

Definition at line 202 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_effort_limits_
protected

Definition at line 208 of file generic_hw_interface.h.

std::vector<std::string> ros_control_boilerplate::GenericHWInterface::joint_names_
protected

Definition at line 186 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_position_
protected

Definition at line 195 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_position_command_
protected

Definition at line 200 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_position_lower_limits_
protected

Definition at line 205 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_position_upper_limits_
protected

Definition at line 206 of file generic_hw_interface.h.

hardware_interface::JointStateInterface ros_control_boilerplate::GenericHWInterface::joint_state_interface_
protected

Definition at line 170 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_velocity_
protected

Definition at line 196 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_velocity_command_
protected

Definition at line 201 of file generic_hw_interface.h.

std::vector<double> ros_control_boilerplate::GenericHWInterface::joint_velocity_limits_
protected

Definition at line 207 of file generic_hw_interface.h.

std::string ros_control_boilerplate::GenericHWInterface::name_
protected

Definition at line 164 of file generic_hw_interface.h.

ros::NodeHandle ros_control_boilerplate::GenericHWInterface::nh_
protected

Definition at line 167 of file generic_hw_interface.h.

std::size_t ros_control_boilerplate::GenericHWInterface::num_joints_
protected

Definition at line 187 of file generic_hw_interface.h.

joint_limits_interface::PositionJointSaturationInterface ros_control_boilerplate::GenericHWInterface::pos_jnt_sat_interface_
protected

Definition at line 176 of file generic_hw_interface.h.

joint_limits_interface::PositionJointSoftLimitsInterface ros_control_boilerplate::GenericHWInterface::pos_jnt_soft_limits_
protected

Definition at line 181 of file generic_hw_interface.h.

hardware_interface::PositionJointInterface ros_control_boilerplate::GenericHWInterface::position_joint_interface_
protected

Definition at line 171 of file generic_hw_interface.h.

urdf::Model* ros_control_boilerplate::GenericHWInterface::urdf_model_
protected

Definition at line 188 of file generic_hw_interface.h.

bool ros_control_boilerplate::GenericHWInterface::use_rosparam_joint_limits_
protected

Definition at line 191 of file generic_hw_interface.h.

bool ros_control_boilerplate::GenericHWInterface::use_soft_limits_if_available_
protected

Definition at line 192 of file generic_hw_interface.h.

joint_limits_interface::VelocityJointSaturationInterface ros_control_boilerplate::GenericHWInterface::vel_jnt_sat_interface_
protected

Definition at line 177 of file generic_hw_interface.h.

joint_limits_interface::VelocityJointSoftLimitsInterface ros_control_boilerplate::GenericHWInterface::vel_jnt_soft_limits_
protected

Definition at line 182 of file generic_hw_interface.h.

hardware_interface::VelocityJointInterface ros_control_boilerplate::GenericHWInterface::velocity_joint_interface_
protected

Definition at line 172 of file generic_hw_interface.h.


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


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Thu Feb 25 2021 03:58:54