#include <ROSInterface.h>

Public Member Functions | |
| void | createPublisher (ros::NodeHandle &nh) |
| DVLSensorToROS (DVLSensor *sensor, std::string topic, int rate) | |
| void | publish () |
| ~DVLSensorToROS () | |
Private Attributes | |
| DVLSensor * | sensor_ |
Definition at line 346 of file ROSInterface.h.
| DVLSensorToROS::DVLSensorToROS | ( | DVLSensor * | sensor, |
| std::string | topic, | ||
| int | rate | ||
| ) | [inline] |
Definition at line 351 of file ROSInterface.h.
| DVLSensorToROS::~DVLSensorToROS | ( | ) | [inline] |
Definition at line 360 of file ROSInterface.h.
| void DVLSensorToROS::createPublisher | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 597 of file ROSInterface.cpp.
| void DVLSensorToROS::publish | ( | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 603 of file ROSInterface.cpp.
DVLSensor* DVLSensorToROS::sensor_ [private] |
Definition at line 348 of file ROSInterface.h.