Public Member Functions | Private Attributes | List of all members
moveit_sim_controller::MoveItSimHWInterface Class Reference

#include <moveit_sim_hw_interface.h>

Inheritance diagram for moveit_sim_controller::MoveItSimHWInterface:
Inheritance graph
[legend]

Public Member Functions

void init ()
 Initialize the robot hardware interface. More...
 
void loadDefaultJointValues ()
 
 MoveItSimHWInterface (ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
 Constructor. More...
 
- Public Member Functions inherited from ros_control_boilerplate::SimHWInterface
virtual void enforceLimits (ros::Duration &period)
 
virtual void read (ros::Duration &elapsed_time)
 
 SimHWInterface (ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
 
virtual void write (ros::Duration &elapsed_time)
 
- 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
 
virtual void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
 GenericHWInterface (ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
 
std::string printCommandHelper ()
 
virtual void printState ()
 
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)
 
virtual void reset ()
 
virtual ~GenericHWInterface ()
 
- 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)
 

Private Attributes

std::string joint_model_group_
 
std::string joint_model_group_pose_
 
std::string name_
 
robot_model_loader::RobotModelLoaderPtr robot_model_loader_
 

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::SimHWInterface
virtual void positionControlSimulation (ros::Duration &elapsed_time, const std::size_t joint_id)
 
- Protected Member Functions inherited from ros_control_boilerplate::GenericHWInterface
virtual void loadURDF (ros::NodeHandle &nh, std::string param_name)
 
- Protected Attributes inherited from ros_control_boilerplate::SimHWInterface
std::vector< double > joint_position_prev_
 
std::string name_
 
double p_error_
 
int sim_control_mode_
 
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_
 

Detailed Description

Definition at line 55 of file moveit_sim_hw_interface.h.

Constructor & Destructor Documentation

moveit_sim_controller::MoveItSimHWInterface::MoveItSimHWInterface ( ros::NodeHandle nh,
urdf::Model urdf_model = NULL 
)
explicit

Constructor.

Definition at line 46 of file moveit_sim_hw_interface.cpp.

Member Function Documentation

void moveit_sim_controller::MoveItSimHWInterface::init ( )
virtual

Initialize the robot hardware interface.

Reimplemented from ros_control_boilerplate::SimHWInterface.

Definition at line 57 of file moveit_sim_hw_interface.cpp.

void moveit_sim_controller::MoveItSimHWInterface::loadDefaultJointValues ( )

Definition at line 71 of file moveit_sim_hw_interface.cpp.

Member Data Documentation

std::string moveit_sim_controller::MoveItSimHWInterface::joint_model_group_
private

Definition at line 71 of file moveit_sim_hw_interface.h.

std::string moveit_sim_controller::MoveItSimHWInterface::joint_model_group_pose_
private

Definition at line 72 of file moveit_sim_hw_interface.h.

std::string moveit_sim_controller::MoveItSimHWInterface::name_
private

Definition at line 69 of file moveit_sim_hw_interface.h.

robot_model_loader::RobotModelLoaderPtr moveit_sim_controller::MoveItSimHWInterface::robot_model_loader_
private

Definition at line 76 of file moveit_sim_hw_interface.h.


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


moveit_sim_controller
Author(s): Dave Coleman
autogenerated on Sat Jul 18 2020 03:40:18