Class for cameras video capture for ROS cameras. More...
#include <vpROSGrabber.h>
Public Member Functions | |
void | acquire (vpImage< unsigned char > &I) |
void | acquire (vpImage< vpRGBa > &I) |
cv::Mat | acquire () |
void | acquire (vpImage< unsigned char > &I, struct timespec ×tamp) |
void | acquire (vpImage< vpRGBa > &I, struct timespec ×tamp) |
cv::Mat | acquire (struct timespec ×tamp) |
bool | acquireNoWait (vpImage< unsigned char > &I) |
bool | acquireNoWait (vpImage< vpRGBa > &I) |
bool | acquireNoWait (vpImage< unsigned char > &I, struct timespec ×tamp) |
bool | acquireNoWait (vpImage< vpRGBa > &I, struct timespec ×tamp) |
void | close () |
bool | getCameraInfo (vpCameraParameters &cam) |
void | getHeight (unsigned short &height) const |
unsigned short | getHeight () const |
void | getWidth (unsigned short &width) const |
unsigned short | getWidth () const |
void | open (int argc, char **argv) |
void | open () |
void | open (vpImage< unsigned char > &I) |
void | open (vpImage< vpRGBa > &I) |
void | setCameraInfoTopic (std::string topic_name) |
void | setFlip (bool flipType) |
void | setImageTopic (std::string topic_name) |
void | setImageTransport (std::string image_transport) |
void | setMasterURI (std::string master_uri) |
void | setNodespace (std::string nodespace) |
void | setRectify (bool rectify) |
vpROSGrabber () | |
virtual | ~vpROSGrabber () |
Protected Member Functions | |
void | imageCallback (const sensor_msgs::CompressedImage::ConstPtr &msg) |
void | imageCallbackRaw (const sensor_msgs::Image::ConstPtr &msg) |
void | paramCallback (const sensor_msgs::CameraInfo::ConstPtr &msg) |
Protected Attributes | |
vpCameraParameters | _cam |
std::string | _image_transport |
std::string | _master_uri |
std::string | _nodespace |
volatile uint32_t | _nsec |
volatile bool | _rectify |
volatile uint32_t | _sec |
std::string | _topic_image |
std::string | _topic_info |
cv::Mat | data |
volatile bool | first_img_received |
volatile bool | first_param_received |
bool | flip |
ros::Subscriber | image_data |
ros::Subscriber | image_info |
volatile bool | isInitialized |
volatile bool | mutex_image |
volatile bool | mutex_param |
ros::NodeHandle * | n |
image_geometry::PinholeCameraModel | p |
ros::AsyncSpinner * | spinner |
volatile unsigned short | usHeight |
volatile unsigned short | usWidth |
Class for cameras video capture for ROS cameras.
Needs OpenCV available on http://opencv.willowgarage.com/wiki/. Needs pthread
The code below shows how to use this class.
#include <visp/vpImage.h> #include <visp/vpImageIo.h> #include <visp_ros/vpROSGrabber.h> int main() { #if defined(VISP_HAVE_OPENCV) vpImage<unsigned char> I; // Create a gray level image container vpROSGrabber g; // Create a grabber for ROS g.setCameraInfoTopic("/camera/camera_info"); g.setImageTopic("/camera/image_raw"); g.setRectify(true); g.open(I); // Open the framegrabber g.acquire(I); // Acquire an image vpImageIo::writePGM(I, "image.pgm"); // Write image on the disk #endif }
Definition at line 104 of file vpROSGrabber.h.
Basic Constructor that subscribes to the "image" and "camera_info" ROS topics.
Definition at line 63 of file vpROSGrabber.cpp.
vpROSGrabber::~vpROSGrabber | ( | ) | [virtual] |
Basic destructor that calls the close() method.
Definition at line 88 of file vpROSGrabber.cpp.
void vpROSGrabber::acquire | ( | vpImage< unsigned char > & | I | ) |
Grab a gray level image
I | : Acquired gray level image. |
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 372 of file vpROSGrabber.cpp.
void vpROSGrabber::acquire | ( | vpImage< vpRGBa > & | I | ) |
Grab a color image
I | : Acquired color image. |
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 407 of file vpROSGrabber.cpp.
cv::Mat vpROSGrabber::acquire | ( | ) |
Grab an image direclty in the OpenCV format.
vpFrameGrabberException::initializationError | If the initialization of the grabber was not done previously. |
Definition at line 442 of file vpROSGrabber.cpp.
void vpROSGrabber::acquire | ( | vpImage< unsigned char > & | I, |
struct timespec & | timestamp | ||
) |
Grab a gray level image with timestamp
I | : Acquired gray level image. |
timestamp | : timestamp of the acquired image. |
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 222 of file vpROSGrabber.cpp.
void vpROSGrabber::acquire | ( | vpImage< vpRGBa > & | I, |
struct timespec & | timestamp | ||
) |
Grab a color image with timestamp
I | : Acquired color image. |
timestamp | : timestamp of the acquired image. |
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 283 of file vpROSGrabber.cpp.
cv::Mat vpROSGrabber::acquire | ( | struct timespec & | timestamp | ) |
Grab an image direclty in the OpenCV format.
timestamp | : timestamp of the acquired image. |
vpFrameGrabberException::initializationError | If the initialization of the grabber was not done previously. |
Definition at line 344 of file vpROSGrabber.cpp.
bool vpROSGrabber::acquireNoWait | ( | vpImage< unsigned char > & | I | ) |
Grab a gray level image without waiting.
I | : Acquired gray level image. |
vpFrameGrabberException::initializationError | If the |
Initialization of the grabber was not done previously.
Definition at line 391 of file vpROSGrabber.cpp.
bool vpROSGrabber::acquireNoWait | ( | vpImage< vpRGBa > & | I | ) |
Grab a color image without waiting.
I | : Acquired color image. |
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 426 of file vpROSGrabber.cpp.
bool vpROSGrabber::acquireNoWait | ( | vpImage< unsigned char > & | I, |
struct timespec & | timestamp | ||
) |
Grab a gray level image with timestamp without waiting.
I | : Acquired gray level image. |
timestamp | : timestamp of the acquired image. |
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 253 of file vpROSGrabber.cpp.
bool vpROSGrabber::acquireNoWait | ( | vpImage< vpRGBa > & | I, |
struct timespec & | timestamp | ||
) |
Grab a color image with timestamp without waiting.
I | : Acquired color image. |
timestamp | : timestamp of the acquired image. |
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 314 of file vpROSGrabber.cpp.
void vpROSGrabber::close | ( | ) |
Definition at line 449 of file vpROSGrabber.cpp.
bool vpROSGrabber::getCameraInfo | ( | vpCameraParameters & | cam | ) |
Get the vpCameraParameters from the camera
cam | parameter of the camera |
Definition at line 610 of file vpROSGrabber.cpp.
void vpROSGrabber::getHeight | ( | unsigned short & | height | ) | const |
Get the height of the image.
height | : height of the image. |
Definition at line 506 of file vpROSGrabber.cpp.
unsigned short vpROSGrabber::getHeight | ( | ) | const |
Get the height of the image.
Definition at line 529 of file vpROSGrabber.cpp.
void vpROSGrabber::getWidth | ( | unsigned short & | width | ) | const |
Get the width of the image.
width | : width of the image. |
Definition at line 493 of file vpROSGrabber.cpp.
unsigned short vpROSGrabber::getWidth | ( | ) | const |
Get the width of the image.
Definition at line 518 of file vpROSGrabber.cpp.
void vpROSGrabber::imageCallback | ( | const sensor_msgs::CompressedImage::ConstPtr & | msg | ) | [protected] |
Definition at line 628 of file vpROSGrabber.cpp.
void vpROSGrabber::imageCallbackRaw | ( | const sensor_msgs::Image::ConstPtr & | msg | ) | [protected] |
Definition at line 649 of file vpROSGrabber.cpp.
void vpROSGrabber::open | ( | int | argc, |
char ** | argv | ||
) |
Initialization of the grabber. Generic initialization of the grabber using parameter from the main function To be used to create ros node that can be started with rosrun
argc | : number of arguments from the main function |
argv | : arguments from the main function |
Definition at line 106 of file vpROSGrabber.cpp.
void vpROSGrabber::open | ( | ) |
Initialization of the grabber.
Generic initialization of the grabber.
vpFrameGrabberException::initializationError | If ROS has already been initialised with a different master_URI. |
Definition at line 150 of file vpROSGrabber.cpp.
void vpROSGrabber::open | ( | vpImage< unsigned char > & | I | ) |
Initialization of the grabber.
Call the generic initialization method.
I | : Gray level image. This parameter is not used. |
Definition at line 186 of file vpROSGrabber.cpp.
void vpROSGrabber::open | ( | vpImage< vpRGBa > & | I | ) |
Initialization of the grabber.
Call the generic initialization method.
I | : Color image. This parameter is not used. |
Definition at line 202 of file vpROSGrabber.cpp.
void vpROSGrabber::paramCallback | ( | const sensor_msgs::CameraInfo::ConstPtr & | msg | ) | [protected] |
Definition at line 676 of file vpROSGrabber.cpp.
void vpROSGrabber::setCameraInfoTopic | ( | std::string | topic_name | ) |
Set the ROS topic name for CameraInfo
topic_name | name of the topic. |
Definition at line 542 of file vpROSGrabber.cpp.
void vpROSGrabber::setFlip | ( | bool | flipType | ) |
Set the boolean variable flip to the expected value.
flipType | : Expected value of the variable flip. True means that the image is flipped during each image acquisition. |
Definition at line 468 of file vpROSGrabber.cpp.
void vpROSGrabber::setImageTopic | ( | std::string | topic_name | ) |
Set the ROS topic name for Images
topic_name | name of the topic. |
Definition at line 555 of file vpROSGrabber.cpp.
void vpROSGrabber::setImageTransport | ( | std::string | image_transport | ) |
Set the image_transport type of the image topic. Values should be :
image_transport | type of transport of the image topic |
Definition at line 597 of file vpROSGrabber.cpp.
void vpROSGrabber::setMasterURI | ( | std::string | master_uri | ) |
Set the URI for ROS Master
master_uri | URI of the master ("http://127.0.0.1:11311") |
Definition at line 568 of file vpROSGrabber.cpp.
void vpROSGrabber::setNodespace | ( | std::string | nodespace | ) |
Set the nodespace
nodespace | Namespace of the connected camera (nodespace is appended to the all topic names) |
Definition at line 580 of file vpROSGrabber.cpp.
void vpROSGrabber::setRectify | ( | bool | rectify | ) |
Set the boolean variable rectify to the expected value.
rectify | : Expected value of the variable rectify. True means that the image is rectified during each image acquisition. |
Definition at line 481 of file vpROSGrabber.cpp.
vpCameraParameters vpROSGrabber::_cam [protected] |
Definition at line 129 of file vpROSGrabber.h.
std::string vpROSGrabber::_image_transport [protected] |
Definition at line 128 of file vpROSGrabber.h.
std::string vpROSGrabber::_master_uri [protected] |
Definition at line 124 of file vpROSGrabber.h.
std::string vpROSGrabber::_nodespace [protected] |
Definition at line 127 of file vpROSGrabber.h.
volatile uint32_t vpROSGrabber::_nsec [protected] |
Definition at line 123 of file vpROSGrabber.h.
volatile bool vpROSGrabber::_rectify [protected] |
Definition at line 117 of file vpROSGrabber.h.
volatile uint32_t vpROSGrabber::_sec [protected] |
Definition at line 123 of file vpROSGrabber.h.
std::string vpROSGrabber::_topic_image [protected] |
Definition at line 125 of file vpROSGrabber.h.
std::string vpROSGrabber::_topic_info [protected] |
Definition at line 126 of file vpROSGrabber.h.
cv::Mat vpROSGrabber::data [protected] |
Definition at line 115 of file vpROSGrabber.h.
volatile bool vpROSGrabber::first_img_received [protected] |
Definition at line 122 of file vpROSGrabber.h.
volatile bool vpROSGrabber::first_param_received [protected] |
Definition at line 122 of file vpROSGrabber.h.
bool vpROSGrabber::flip [protected] |
Definition at line 116 of file vpROSGrabber.h.
ros::Subscriber vpROSGrabber::image_data [protected] |
Definition at line 108 of file vpROSGrabber.h.
ros::Subscriber vpROSGrabber::image_info [protected] |
Definition at line 109 of file vpROSGrabber.h.
volatile bool vpROSGrabber::isInitialized [protected] |
Definition at line 111 of file vpROSGrabber.h.
volatile bool vpROSGrabber::mutex_image [protected] |
Definition at line 118 of file vpROSGrabber.h.
volatile bool vpROSGrabber::mutex_param [protected] |
Definition at line 118 of file vpROSGrabber.h.
ros::NodeHandle* vpROSGrabber::n [protected] |
Definition at line 107 of file vpROSGrabber.h.
image_geometry::PinholeCameraModel vpROSGrabber::p [protected] |
Definition at line 114 of file vpROSGrabber.h.
ros::AsyncSpinner* vpROSGrabber::spinner [protected] |
Definition at line 110 of file vpROSGrabber.h.
volatile unsigned short vpROSGrabber::usHeight [protected] |
Definition at line 113 of file vpROSGrabber.h.
volatile unsigned short vpROSGrabber::usWidth [protected] |
Definition at line 112 of file vpROSGrabber.h.