#include <ROSInterface.h>
Public Member Functions | |
virtual void | createSubscriber (ros::NodeHandle &nh) |
virtual void | processData (const sensor_msgs::ImageConstPtr &msg) |
ROSImageToHUDCamera (std::string topic, std::string info_topic, boost::shared_ptr< HUDCamera > camera) | |
~ROSImageToHUDCamera () | |
Private Attributes | |
boost::shared_ptr< HUDCamera > | cam |
image_transport::Subscriber | image_sub |
std::string | image_topic |
boost::shared_ptr < image_transport::ImageTransport > | it |
Definition at line 220 of file ROSInterface.h.
ROSImageToHUDCamera::ROSImageToHUDCamera | ( | std::string | topic, |
std::string | info_topic, | ||
boost::shared_ptr< HUDCamera > | camera | ||
) |
Definition at line 322 of file ROSInterface.cpp.
Definition at line 359 of file ROSInterface.cpp.
void ROSImageToHUDCamera::createSubscriber | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements ROSSubscriberInterface.
Definition at line 327 of file ROSInterface.cpp.
void ROSImageToHUDCamera::processData | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [virtual] |
Definition at line 337 of file ROSInterface.cpp.
boost::shared_ptr<HUDCamera> ROSImageToHUDCamera::cam [private] |
Definition at line 222 of file ROSInterface.h.
Definition at line 224 of file ROSInterface.h.
std::string ROSImageToHUDCamera::image_topic [private] |
Definition at line 225 of file ROSInterface.h.
boost::shared_ptr<image_transport::ImageTransport> ROSImageToHUDCamera::it [private] |
Definition at line 223 of file ROSInterface.h.