Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ros_control_boilerplate::SimHWInterface Class Reference

Hardware interface for a robot. More...

#include <sim_hw_interface.h>

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

Public Member Functions

virtual void enforceLimits (ros::Duration &period)
 
virtual void init ()
 Initialize the robot hardware interface. More...
 
virtual void read (ros::Duration &elapsed_time)
 Read the state from the robot hardware. More...
 
 SimHWInterface (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 (const ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
 Constructor. 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 (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 (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 positionControlSimulation (ros::Duration &elapsed_time, const std::size_t joint_id)
 Basic model of system for position control. More...
 
- Protected Member Functions inherited from ros_control_boilerplate::GenericHWInterface
virtual void loadURDF (const ros::NodeHandle &nh, std::string param_name)
 Get the URDF XML from the parameter server. More...
 

Protected Attributes

std::vector< double > joint_position_prev_
 
std::string name_
 
double p_error_
 
int sim_control_mode_ = 0
 
double v_error_
 
- 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_
 

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 49 of file sim_hw_interface.h.

Constructor & Destructor Documentation

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

Constructor.

Parameters
nh- Node handle for topics.

Definition at line 47 of file sim_hw_interface.cpp.

Member Function Documentation

void ros_control_boilerplate::SimHWInterface::enforceLimits ( ros::Duration period)
virtual

Enforce limits for all values before writing

Implements ros_control_boilerplate::GenericHWInterface.

Definition at line 121 of file sim_hw_interface.cpp.

void ros_control_boilerplate::SimHWInterface::init ( )
virtual

Initialize the robot hardware interface.

Reimplemented from ros_control_boilerplate::GenericHWInterface.

Definition at line 63 of file sim_hw_interface.cpp.

void ros_control_boilerplate::SimHWInterface::positionControlSimulation ( ros::Duration elapsed_time,
const std::size_t  joint_id 
)
protectedvirtual

Basic model of system for position control.

Definition at line 127 of file sim_hw_interface.cpp.

void ros_control_boilerplate::SimHWInterface::read ( ros::Duration elapsed_time)
virtual

Read the state from the robot hardware.

Implements ros_control_boilerplate::GenericHWInterface.

Definition at line 74 of file sim_hw_interface.cpp.

void ros_control_boilerplate::SimHWInterface::write ( ros::Duration elapsed_time)
virtual

Write the command to the robot hardware.

Implements ros_control_boilerplate::GenericHWInterface.

Definition at line 79 of file sim_hw_interface.cpp.

Member Data Documentation

std::vector<double> ros_control_boilerplate::SimHWInterface::joint_position_prev_
protected

Definition at line 83 of file sim_hw_interface.h.

std::string ros_control_boilerplate::SimHWInterface::name_
protected

Definition at line 76 of file sim_hw_interface.h.

double ros_control_boilerplate::SimHWInterface::p_error_
protected

Definition at line 79 of file sim_hw_interface.h.

int ros_control_boilerplate::SimHWInterface::sim_control_mode_ = 0
protected

Definition at line 86 of file sim_hw_interface.h.

double ros_control_boilerplate::SimHWInterface::v_error_
protected

Definition at line 80 of file sim_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