#include <PanolutVirtualCameraNodelet.h>
Public Member Functions | |
bool | getVirtualCameraConfigService (GetVirtualCameraConfig::Request &request, GetVirtualCameraConfig::Response &response) |
void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
void | onInit () |
PanolutVirtualCameraNodelet () | |
void | setup (ros::NodeHandle &nh, ros::NodeHandle &pnh) |
void | tfPublisherCallback (const ros::TimerEvent &event) |
void | virtualCameraConfigCallback (const VirtualCameraConfig::ConstPtr &msg) |
Private Member Functions | |
void | updateTransform () |
Private Attributes | |
bool | alpha |
sensor_msgs::CameraInfo | camMsg |
ros::Publisher | camPub |
bool | equalizeHist |
std::string | frameId |
ros::ServiceServer | getVirtualCameraConfigServer |
image_transport::Subscriber | imageSubcriber |
int | inHeight |
int | inWidth |
boost::shared_ptr < image_transport::ImageTransport > | it |
bool | lookupTablesLoaded |
std::string | lutPath |
image_transport::Publisher | outPub |
omnicamera::LookupStitcher | pano |
int | panoHeight |
int | panoWidth |
std::string | parentFrameId |
int | radius |
ros::Timer | tfPublisherTimer |
tf::Transform | transform |
omnicamera::LookupStitcher | vcam |
VirtualCameraConfig | vcamConfig |
ros::Subscriber | virtualCameraConfigSubscriber |
Static Private Attributes | |
static const int | N_CAMS = 6 |
Definition at line 24 of file PanolutVirtualCameraNodelet.h.
Definition at line 25 of file PanolutVirtualCameraNodelet.cpp.
bool omnicamera::PanolutVirtualCameraNodelet::getVirtualCameraConfigService | ( | GetVirtualCameraConfig::Request & | request, |
GetVirtualCameraConfig::Response & | response | ||
) |
Service for getting current virtual camera config.
Definition at line 180 of file PanolutVirtualCameraNodelet.cpp.
void omnicamera::PanolutVirtualCameraNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) |
Callback for camera images, yields rendering and publishing new virtual camera view.
Definition at line 185 of file PanolutVirtualCameraNodelet.cpp.
Nodelet initialization callback.
Definition at line 117 of file PanolutVirtualCameraNodelet.cpp.
void omnicamera::PanolutVirtualCameraNodelet::setup | ( | ros::NodeHandle & | nh, |
ros::NodeHandle & | pnh | ||
) |
Parses parameters using node handles, setup publishers and subscribers etc.
Definition at line 29 of file PanolutVirtualCameraNodelet.cpp.
void omnicamera::PanolutVirtualCameraNodelet::tfPublisherCallback | ( | const ros::TimerEvent & | event | ) |
Callback called by a timer to publish tf messages.
Definition at line 131 of file PanolutVirtualCameraNodelet.cpp.
void omnicamera::PanolutVirtualCameraNodelet::updateTransform | ( | ) | [private] |
Definition at line 136 of file PanolutVirtualCameraNodelet.cpp.
void omnicamera::PanolutVirtualCameraNodelet::virtualCameraConfigCallback | ( | const VirtualCameraConfig::ConstPtr & | msg | ) |
Callback for updating virtual camera config.
Definition at line 143 of file PanolutVirtualCameraNodelet.cpp.
bool omnicamera::PanolutVirtualCameraNodelet::alpha [private] |
Flag indicating whether alpha masks are used.
Definition at line 72 of file PanolutVirtualCameraNodelet.h.
sensor_msgs::CameraInfo omnicamera::PanolutVirtualCameraNodelet::camMsg [private] |
Camera info message template. Updated when camera configuration (field of view, width, height) changes, and sent for each image sent.
Definition at line 130 of file PanolutVirtualCameraNodelet.h.
ros::Publisher omnicamera::PanolutVirtualCameraNodelet::camPub [private] |
Camera info publisher.
Definition at line 122 of file PanolutVirtualCameraNodelet.h.
bool omnicamera::PanolutVirtualCameraNodelet::equalizeHist [private] |
Indicates whether histogram equalization should be performed prior to publishing the image.
Definition at line 89 of file PanolutVirtualCameraNodelet.h.
std::string omnicamera::PanolutVirtualCameraNodelet::frameId [private] |
Virtual camera frame ID.
Definition at line 80 of file PanolutVirtualCameraNodelet.h.
ros::ServiceServer omnicamera::PanolutVirtualCameraNodelet::getVirtualCameraConfigServer [private] |
Virtual camera config service server.
Definition at line 114 of file PanolutVirtualCameraNodelet.h.
image_transport::Subscriber omnicamera::PanolutVirtualCameraNodelet::imageSubcriber [private] |
Image subscriber.
Definition at line 106 of file PanolutVirtualCameraNodelet.h.
int omnicamera::PanolutVirtualCameraNodelet::inHeight [private] |
Input image height.
Definition at line 60 of file PanolutVirtualCameraNodelet.h.
int omnicamera::PanolutVirtualCameraNodelet::inWidth [private] |
Input image width.
Definition at line 56 of file PanolutVirtualCameraNodelet.h.
boost::shared_ptr<image_transport::ImageTransport> omnicamera::PanolutVirtualCameraNodelet::it [private] |
Image transport, seems to be needed to avoid image transport subscribers/publishers going out of scope.
Definition at line 102 of file PanolutVirtualCameraNodelet.h.
bool omnicamera::PanolutVirtualCameraNodelet::lookupTablesLoaded [private] |
Flag indicating whether look-up tables are loaded.
Definition at line 134 of file PanolutVirtualCameraNodelet.h.
std::string omnicamera::PanolutVirtualCameraNodelet::lutPath [private] |
Path for look-up table files.
Definition at line 78 of file PanolutVirtualCameraNodelet.h.
const int omnicamera::PanolutVirtualCameraNodelet::N_CAMS = 6 [static, private] |
Definition at line 52 of file PanolutVirtualCameraNodelet.h.
image_transport::Publisher omnicamera::PanolutVirtualCameraNodelet::outPub [private] |
Virtual camera view publisher.
Definition at line 118 of file PanolutVirtualCameraNodelet.h.
Panorama look-up table stitcher.
Definition at line 94 of file PanolutVirtualCameraNodelet.h.
int omnicamera::PanolutVirtualCameraNodelet::panoHeight [private] |
Panorama height.
Definition at line 68 of file PanolutVirtualCameraNodelet.h.
int omnicamera::PanolutVirtualCameraNodelet::panoWidth [private] |
Panorama width.
Definition at line 64 of file PanolutVirtualCameraNodelet.h.
std::string omnicamera::PanolutVirtualCameraNodelet::parentFrameId [private] |
Parent frame id, tf messages are sent for parentFrameId -> frameId link.
Definition at line 82 of file PanolutVirtualCameraNodelet.h.
int omnicamera::PanolutVirtualCameraNodelet::radius [private] |
Sphere radius for panorama stitching.
Definition at line 76 of file PanolutVirtualCameraNodelet.h.
ros::Timer omnicamera::PanolutVirtualCameraNodelet::tfPublisherTimer [private] |
Timer for publishing tf messages.
Definition at line 84 of file PanolutVirtualCameraNodelet.h.
tf::Transform omnicamera::PanolutVirtualCameraNodelet::transform [private] |
Transform to be published. Updated only when camera config changes.
Definition at line 86 of file PanolutVirtualCameraNodelet.h.
Virtual camera look-up table stitcher.
Definition at line 98 of file PanolutVirtualCameraNodelet.h.
VirtualCameraConfig omnicamera::PanolutVirtualCameraNodelet::vcamConfig [private] |
Current virtual camera configuration, updated from a subscribed topic.
Definition at line 126 of file PanolutVirtualCameraNodelet.h.
ros::Subscriber omnicamera::PanolutVirtualCameraNodelet::virtualCameraConfigSubscriber [private] |
Virtual camera config subscriber.
Definition at line 110 of file PanolutVirtualCameraNodelet.h.