Public Member Functions | List of all members
rrbot_control::RRBotHWInterface Class Reference

Hardware interface for a robot. More...

#include <rrbot_hw_interface.h>

Inheritance diagram for rrbot_control::RRBotHWInterface:
Inheritance graph
[legend]

Public Member Functions

virtual void enforceLimits (ros::Duration &period)
 
virtual void read (ros::Duration &elapsed_time)
 Read the state from the robot hardware. More...
 
 RRBotHWInterface (ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
 Constructor. More...
 
virtual void write (ros::Duration &elapsed_time)
 Write the command to the robot hardware. More...
 
- Public Member Functions inherited from ros_control_boilerplate::GenericHWInterface
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...
 
 GenericHWInterface (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 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 ~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)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
 RobotHW ()
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
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)
 

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
 
- Protected Member Functions inherited from ros_control_boilerplate::GenericHWInterface
virtual void loadURDF (ros::NodeHandle &nh, std::string param_name)
 Get the URDF XML from the parameter server. More...
 
- Protected Attributes inherited from ros_control_boilerplate::GenericHWInterface
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_
 

Detailed Description

Hardware interface for a robot.

Definition at line 49 of file rrbot_hw_interface.h.

Constructor & Destructor Documentation

rrbot_control::RRBotHWInterface::RRBotHWInterface ( ros::NodeHandle nh,
urdf::Model urdf_model = NULL 
)

Constructor.

Parameters
nh- Node handle for topics.

Definition at line 45 of file rrbot_hw_interface.cpp.

Member Function Documentation

void rrbot_control::RRBotHWInterface::enforceLimits ( ros::Duration period)
virtual

Enforce limits for all values before writing

Implements ros_control_boilerplate::GenericHWInterface.

Definition at line 89 of file rrbot_hw_interface.cpp.

void rrbot_control::RRBotHWInterface::read ( ros::Duration elapsed_time)
virtual

Read the state from the robot hardware.

Implements ros_control_boilerplate::GenericHWInterface.

Definition at line 51 of file rrbot_hw_interface.cpp.

void rrbot_control::RRBotHWInterface::write ( ros::Duration elapsed_time)
virtual

Write the command to the robot hardware.

Implements ros_control_boilerplate::GenericHWInterface.

Definition at line 64 of file rrbot_hw_interface.cpp.


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


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Sat Jun 8 2019 18:06:50