#include <ROSInterface.h>

Public Member Functions | |
| ArmToROSJointState (SimulatedIAUV *arm, std::string topic, int rate) | |
| void | createPublisher (ros::NodeHandle &nh) |
| void | publish () |
| ~ArmToROSJointState () | |
Private Attributes | |
| boost::shared_ptr< URDFRobot > | arm |
Definition at line 365 of file ROSInterface.h.
| ArmToROSJointState::ArmToROSJointState | ( | SimulatedIAUV * | arm, |
| std::string | topic, | ||
| int | rate | ||
| ) |
Definition at line 618 of file ROSInterface.cpp.
Definition at line 649 of file ROSInterface.cpp.
| void ArmToROSJointState::createPublisher | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 624 of file ROSInterface.cpp.
| void ArmToROSJointState::publish | ( | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 630 of file ROSInterface.cpp.
boost::shared_ptr<URDFRobot> ArmToROSJointState::arm [private] |
Definition at line 367 of file ROSInterface.h.