Public Member Functions | Protected Member Functions | Protected Attributes
ros_control_boilerplate::GenericHWInterface Class Reference

Hardware interface for a robot. More...

#include <generic_hw_interface.h>

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

List of all members.

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()
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.
virtual void enforceLimits (ros::Duration &period)=0
 GenericHWInterface (ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
 Constructor.
virtual void init ()
 Initialize the hardware interface.
std::string printCommandHelper ()
 Helper for debugging a joint's command.
virtual void printState ()
 Helper for debugging a joint's state.
std::string printStateHelper ()
virtual void read (ros::Duration &elapsed_time)=0
 Read the state from the robot hardware.
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.
virtual void reset ()
 Set all members to default values.
virtual void write (ros::Duration &elapsed_time)=0
 Write the command to the robot hardware.
virtual ~GenericHWInterface ()
 Destructor.

Protected Member Functions

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

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_

Detailed Description

Hardware interface for a robot.

Definition at line 64 of file generic_hw_interface.h.


Constructor & Destructor Documentation

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.

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 [inline, virtual]

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()

Reimplemented from hardware_interface::RobotHW.

Definition at line 95 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 
) [inline, virtual]

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 106 of file generic_hw_interface.h.

Enforce limits for all values before writing

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

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 ( ros::NodeHandle nh,
std::string  param_name 
) [protected, virtual]

Get the URDF XML from the parameter server.

Definition at line 304 of file generic_hw_interface.cpp.

Helper for debugging a joint's command.

Definition at line 290 of file generic_hw_interface.cpp.

Helper for debugging a joint's state.

Definition at line 268 of file generic_hw_interface.cpp.

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.

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.

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.


Member Data Documentation

Definition at line 152 of file generic_hw_interface.h.

Definition at line 157 of file generic_hw_interface.h.

Definition at line 147 of file generic_hw_interface.h.

Definition at line 171 of file generic_hw_interface.h.

Definition at line 176 of file generic_hw_interface.h.

Definition at line 182 of file generic_hw_interface.h.

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

Definition at line 160 of file generic_hw_interface.h.

Definition at line 169 of file generic_hw_interface.h.

Definition at line 174 of file generic_hw_interface.h.

Definition at line 179 of file generic_hw_interface.h.

Definition at line 180 of file generic_hw_interface.h.

Definition at line 144 of file generic_hw_interface.h.

Definition at line 170 of file generic_hw_interface.h.

Definition at line 175 of file generic_hw_interface.h.

Definition at line 181 of file generic_hw_interface.h.

Reimplemented in ros_control_boilerplate::SimHWInterface.

Definition at line 138 of file generic_hw_interface.h.

Definition at line 141 of file generic_hw_interface.h.

Definition at line 161 of file generic_hw_interface.h.

Definition at line 150 of file generic_hw_interface.h.

Definition at line 155 of file generic_hw_interface.h.

Definition at line 145 of file generic_hw_interface.h.

Definition at line 162 of file generic_hw_interface.h.

Definition at line 165 of file generic_hw_interface.h.

Definition at line 166 of file generic_hw_interface.h.

Definition at line 151 of file generic_hw_interface.h.

Definition at line 156 of file generic_hw_interface.h.

Definition at line 146 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 Jun 6 2019 20:37:19