This class defines a ros-control hardware interface. More...
#include <SchunkCanopenHardwareInterface.h>

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) |
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 |
This class defines a ros-control hardware interface.
Definition at line 48 of file SchunkCanopenHardwareInterface.h.
| SchunkCanopenHardwareInterface::SchunkCanopenHardwareInterface | ( | ros::NodeHandle & | nh, |
| boost::shared_ptr< CanOpenController > & | canopen | ||
| ) |
Definition at line 38 of file SchunkCanopenHardwareInterface.cpp.
|
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.
|
virtual |
Initialize the hardware interface.
Definition at line 46 of file SchunkCanopenHardwareInterface.cpp.
|
inline |
Returns true, when at least one node in the hardware is in a fault state.
Definition at line 71 of file SchunkCanopenHardwareInterface.h.
|
virtual |
Reimplemented from hardware_interface::RobotHW.
Definition at line 201 of file SchunkCanopenHardwareInterface.cpp.
|
virtual |
Read the state from the robot hardware.
Definition at line 138 of file SchunkCanopenHardwareInterface.cpp.
|
virtual |
write the command to the robot hardware.
Definition at line 164 of file SchunkCanopenHardwareInterface.cpp.
|
protected |
Definition at line 80 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 98 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 85 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 93 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 100 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 90 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 94 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 95 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 91 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 101 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 83 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 92 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 79 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 89 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 97 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 87 of file SchunkCanopenHardwareInterface.h.
|
protected |
Definition at line 84 of file SchunkCanopenHardwareInterface.h.