#include <ROSInterface.h>

Public Member Functions | |
| contactSensorToROS (osg::Group *rootNode, BulletPhysics *physics, std::string target, std::string topic, int rate) | |
| void | createPublisher (ros::NodeHandle &nh) |
| void | publish () |
| ~contactSensorToROS () | |
Private Attributes | |
| BulletPhysics * | physics |
| osg::Group * | rootNode |
| std::string | target |
Definition at line 408 of file ROSInterface.h.
| contactSensorToROS::contactSensorToROS | ( | osg::Group * | rootNode, |
| BulletPhysics * | physics, | ||
| std::string | target, | ||
| std::string | topic, | ||
| int | rate | ||
| ) |
Definition at line 843 of file ROSInterface.cpp.
Definition at line 892 of file ROSInterface.cpp.
| void contactSensorToROS::createPublisher | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 852 of file ROSInterface.cpp.
| void contactSensorToROS::publish | ( | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 858 of file ROSInterface.cpp.
BulletPhysics* contactSensorToROS::physics [private] |
Definition at line 410 of file ROSInterface.h.
osg::Group* contactSensorToROS::rootNode [private] |
Definition at line 412 of file ROSInterface.h.
std::string contactSensorToROS::target [private] |
Definition at line 411 of file ROSInterface.h.