Public Member Functions | Protected Attributes | List of all members
SchunkCanopenHardwareInterface Class Reference

This class defines a ros-control hardware interface. More...

#include <SchunkCanopenHardwareInterface.h>

Inheritance diagram for SchunkCanopenHardwareInterface:
Inheritance graph
[legend]

Public Member Functions

virtual void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
sensor_msgs::JointState getJointMessage ()
 Creates a joint_state message from the current joint angles and returns it. More...
 
virtual void init ()
 Initialize the hardware interface. More...
 
bool isFault ()
 Returns true, when at least one node in the hardware is in a fault state. More...
 
virtual bool prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
 
virtual void read ()
 Read the state from the robot hardware. More...
 
 SchunkCanopenHardwareInterface (ros::NodeHandle &nh, boost::shared_ptr< CanOpenController > &canopen)
 
virtual void write (ros::Time time, ros::Duration period)
 write the command to the robot hardware. 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 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)
 

Protected Attributes

boost::shared_ptr< CanOpenControllerm_canopen_controller
 
bool m_is_fault
 
joint_limits_interface::PositionJointSoftLimitsInterface m_jnt_limits_interface
 
std::vector< double > m_joint_effort
 
joint_limits_interface::JointLimits m_joint_limits
 
std::vector< std::string > m_joint_names
 
std::vector< double > m_joint_position_commands
 
std::vector< double > m_joint_position_commands_last
 
std::vector< double > m_joint_positions
 
joint_limits_interface::SoftJointLimits m_joint_soft_limits
 
hardware_interface::JointStateInterface m_joint_state_interface
 
std::vector< double > m_joint_velocity
 
ros::NodeHandle m_node_handle
 
std::vector< uint8_tm_node_ids
 
std::vector< bool > m_nodes_in_fault
 
size_t m_num_joints
 
hardware_interface::PositionJointInterface m_position_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

This class defines a ros-control hardware interface.

Definition at line 48 of file SchunkCanopenHardwareInterface.h.

Constructor & Destructor Documentation

SchunkCanopenHardwareInterface::SchunkCanopenHardwareInterface ( ros::NodeHandle nh,
boost::shared_ptr< CanOpenController > &  canopen 
)

Definition at line 38 of file SchunkCanopenHardwareInterface.cpp.

Member Function Documentation

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

Reimplemented from hardware_interface::RobotHW.

Definition at line 206 of file SchunkCanopenHardwareInterface.cpp.

sensor_msgs::JointState SchunkCanopenHardwareInterface::getJointMessage ( )

Creates a joint_state message from the current joint angles and returns it.

Definition at line 211 of file SchunkCanopenHardwareInterface.cpp.

void SchunkCanopenHardwareInterface::init ( )
virtual

Initialize the hardware interface.

Definition at line 46 of file SchunkCanopenHardwareInterface.cpp.

bool SchunkCanopenHardwareInterface::isFault ( )
inline

Returns true, when at least one node in the hardware is in a fault state.

Definition at line 71 of file SchunkCanopenHardwareInterface.h.

bool SchunkCanopenHardwareInterface::prepareSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
virtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 201 of file SchunkCanopenHardwareInterface.cpp.

void SchunkCanopenHardwareInterface::read ( )
virtual

Read the state from the robot hardware.

Definition at line 138 of file SchunkCanopenHardwareInterface.cpp.

void SchunkCanopenHardwareInterface::write ( ros::Time  time,
ros::Duration  period 
)
virtual

write the command to the robot hardware.

Definition at line 164 of file SchunkCanopenHardwareInterface.cpp.

Member Data Documentation

boost::shared_ptr<CanOpenController> SchunkCanopenHardwareInterface::m_canopen_controller
protected

Definition at line 80 of file SchunkCanopenHardwareInterface.h.

bool SchunkCanopenHardwareInterface::m_is_fault
protected

Definition at line 98 of file SchunkCanopenHardwareInterface.h.

joint_limits_interface::PositionJointSoftLimitsInterface SchunkCanopenHardwareInterface::m_jnt_limits_interface
protected

Definition at line 85 of file SchunkCanopenHardwareInterface.h.

std::vector<double> SchunkCanopenHardwareInterface::m_joint_effort
protected

Definition at line 93 of file SchunkCanopenHardwareInterface.h.

joint_limits_interface::JointLimits SchunkCanopenHardwareInterface::m_joint_limits
protected

Definition at line 100 of file SchunkCanopenHardwareInterface.h.

std::vector<std::string> SchunkCanopenHardwareInterface::m_joint_names
protected

Definition at line 90 of file SchunkCanopenHardwareInterface.h.

std::vector<double> SchunkCanopenHardwareInterface::m_joint_position_commands
protected

Definition at line 94 of file SchunkCanopenHardwareInterface.h.

std::vector<double> SchunkCanopenHardwareInterface::m_joint_position_commands_last
protected

Definition at line 95 of file SchunkCanopenHardwareInterface.h.

std::vector<double> SchunkCanopenHardwareInterface::m_joint_positions
protected

Definition at line 91 of file SchunkCanopenHardwareInterface.h.

joint_limits_interface::SoftJointLimits SchunkCanopenHardwareInterface::m_joint_soft_limits
protected

Definition at line 101 of file SchunkCanopenHardwareInterface.h.

hardware_interface::JointStateInterface SchunkCanopenHardwareInterface::m_joint_state_interface
protected

Definition at line 83 of file SchunkCanopenHardwareInterface.h.

std::vector<double> SchunkCanopenHardwareInterface::m_joint_velocity
protected

Definition at line 92 of file SchunkCanopenHardwareInterface.h.

ros::NodeHandle SchunkCanopenHardwareInterface::m_node_handle
protected

Definition at line 79 of file SchunkCanopenHardwareInterface.h.

std::vector<uint8_t> SchunkCanopenHardwareInterface::m_node_ids
protected

Definition at line 89 of file SchunkCanopenHardwareInterface.h.

std::vector<bool> SchunkCanopenHardwareInterface::m_nodes_in_fault
protected

Definition at line 97 of file SchunkCanopenHardwareInterface.h.

size_t SchunkCanopenHardwareInterface::m_num_joints
protected

Definition at line 87 of file SchunkCanopenHardwareInterface.h.

hardware_interface::PositionJointInterface SchunkCanopenHardwareInterface::m_position_joint_interface
protected

Definition at line 84 of file SchunkCanopenHardwareInterface.h.


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


schunk_canopen_driver
Author(s): Felix Mauch , Georg Heppner
autogenerated on Mon Jun 10 2019 15:07:49