Class for cameras video capture for ROS cameras.
More...
#include <vpROSGrabber.h>
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>
{
#if defined(VISP_HAVE_OPENCV)
vpImage<unsigned char> I;
vpImageIo::writePGM(I, "image.pgm");
#endif
}
- Examples:
- tutorial-ros-grabber.cpp, tutorial-ros-pioneer-visual-servo.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.
Definition at line 103 of file vpROSGrabber.h.
vpROSGrabber::vpROSGrabber |
( |
| ) |
|
Basic Constructor that subscribes to the "image" and "camera_info" ROS topics.
Definition at line 63 of file vpROSGrabber.cpp.
vpROSGrabber::~vpROSGrabber |
( |
| ) |
|
|
virtual |
void vpROSGrabber::acquire |
( |
vpImage< unsigned char > & |
I | ) |
|
void vpROSGrabber::acquire |
( |
vpImage< vpRGBa > & |
I | ) |
|
Grab a color image
- Parameters
-
- Exceptions
-
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.
- Returns
- Acquired image.
- Exceptions
-
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
- Parameters
-
I | : Acquired gray level image. |
timestamp | : timestamp of the acquired image. |
- Exceptions
-
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
- Parameters
-
I | : Acquired color image. |
timestamp | : timestamp of the acquired image. |
- Exceptions
-
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.
- Parameters
-
timestamp | : timestamp of the acquired image. |
- Returns
- Acquired image.
- Exceptions
-
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.
- Parameters
-
I | : Acquired gray level image. |
- Returns
- true if a new image was acquired or false if the image is the same than the previous one.
- Exceptions
-
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.
- Parameters
-
- Returns
- true if a new image was acquired or false if the image is the same than the previous one.
- Exceptions
-
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.
- Parameters
-
I | : Acquired gray level image. |
timestamp | : timestamp of the acquired image. |
- Returns
- true if a new image was acquired or false if the image is the same than the previous one.
- Exceptions
-
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.
- Parameters
-
I | : Acquired color image. |
timestamp | : timestamp of the acquired image. |
- Returns
- true if a new image was acquired or false if the image is the same than the previous one.
- Exceptions
-
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 314 of file vpROSGrabber.cpp.
void vpROSGrabber::close |
( |
| ) |
|
bool vpROSGrabber::getCameraInfo |
( |
vpCameraParameters & |
cam | ) |
|
void vpROSGrabber::getHeight |
( |
unsigned short & |
height | ) |
const |
Get the height of the image.
- Parameters
-
height | : height of the image. |
Definition at line 506 of file vpROSGrabber.cpp.
unsigned short vpROSGrabber::getHeight |
( |
| ) |
const |
Get the height of the image.
- Returns
- 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.
- Parameters
-
width | : width of the image. |
Definition at line 493 of file vpROSGrabber.cpp.
unsigned short vpROSGrabber::getWidth |
( |
| ) |
const |
Get the width of the image.
- Returns
- width of the image.
Definition at line 518 of file vpROSGrabber.cpp.
void vpROSGrabber::imageCallback |
( |
const sensor_msgs::CompressedImage::ConstPtr & |
msg | ) |
|
|
protected |
void vpROSGrabber::imageCallbackRaw |
( |
const sensor_msgs::Image::ConstPtr & |
msg | ) |
|
|
protected |
void vpROSGrabber::open |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
void vpROSGrabber::open |
( |
| ) |
|
Initialization of the grabber.
Generic initialization of the grabber.
- Exceptions
-
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.
- Parameters
-
I | : Gray level image. This parameter is not used. |
- See also
- open()
Definition at line 186 of file vpROSGrabber.cpp.
void vpROSGrabber::open |
( |
vpImage< vpRGBa > & |
I | ) |
|
Initialization of the grabber.
Call the generic initialization method.
- Parameters
-
I | : Color image. This parameter is not used. |
- See also
- open()
Definition at line 202 of file vpROSGrabber.cpp.
void vpROSGrabber::paramCallback |
( |
const sensor_msgs::CameraInfo::ConstPtr & |
msg | ) |
|
|
protected |
void vpROSGrabber::setCameraInfoTopic |
( |
std::string |
topic_name | ) |
|
void vpROSGrabber::setFlip |
( |
bool |
flipType | ) |
|
Set the boolean variable flip to the expected value.
- Parameters
-
flipType | : Expected value of the variable flip. True means that the image is flipped during each image acquisition. |
- Warning
- This function is only useful under Windows.
- Note
- The aim of this function is to fix a problem which appears under Windows. Indeed with several cameras the aquired images are flipped.
Definition at line 468 of file vpROSGrabber.cpp.
void vpROSGrabber::setImageTopic |
( |
std::string |
topic_name | ) |
|
void vpROSGrabber::setImageTransport |
( |
std::string |
image_transport | ) |
|
Set the image_transport type of the image topic. Values should be :
- "raw" if images are not compressed
- any other value if the images are compressed (ie "jpeg",...).
- Parameters
-
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
- Parameters
-
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
- Parameters
-
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 | ) |
|
vpCameraParameters vpROSGrabber::_cam |
|
protected |
std::string vpROSGrabber::_image_transport |
|
protected |
std::string vpROSGrabber::_master_uri |
|
protected |
std::string vpROSGrabber::_nodespace |
|
protected |
volatile uint32_t vpROSGrabber::_nsec |
|
protected |
volatile bool vpROSGrabber::_rectify |
|
protected |
volatile uint32_t vpROSGrabber::_sec |
|
protected |
std::string vpROSGrabber::_topic_image |
|
protected |
std::string vpROSGrabber::_topic_info |
|
protected |
cv::Mat vpROSGrabber::data |
|
protected |
volatile bool vpROSGrabber::first_img_received |
|
protected |
volatile bool vpROSGrabber::first_param_received |
|
protected |
volatile bool vpROSGrabber::isInitialized |
|
protected |
volatile bool vpROSGrabber::mutex_image |
|
protected |
volatile bool vpROSGrabber::mutex_param |
|
protected |
volatile unsigned short vpROSGrabber::usHeight |
|
protected |
volatile unsigned short vpROSGrabber::usWidth |
|
protected |
The documentation for this class was generated from the following files: