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-franka-coppeliasim-dual-arm.cpp, tutorial-franka-coppeliasim-ibvs-apriltag.cpp, tutorial-franka-coppeliasim-pbvs-apriltag.cpp, tutorial-ros-grabber.cpp, tutorial-ros-pioneer-visual-servo.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.
Definition at line 104 of file vpROSGrabber.h.
◆ vpROSGrabber()
vpROSGrabber::vpROSGrabber |
( |
| ) |
|
Basic Constructor that subscribes to the "image" and "camera_info" ROS topics.
Definition at line 61 of file vpROSGrabber.cpp.
◆ ~vpROSGrabber()
vpROSGrabber::~vpROSGrabber |
( |
| ) |
|
|
virtual |
◆ acquire() [1/8]
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 473 of file vpROSGrabber.cpp.
◆ acquire() [2/8]
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 385 of file vpROSGrabber.cpp.
◆ acquire() [3/8]
void vpROSGrabber::acquire |
( |
vpImage< unsigned char > & |
I | ) |
|
◆ acquire() [4/8]
void vpROSGrabber::acquire |
( |
vpImage< unsigned char > & |
I, |
|
|
double & |
timestamp_second |
|
) |
| |
Grab a gray level image with timestamp
- Parameters
-
I | : Acquired gray level image. |
timestamp_second | : timestamp expressed in [s] of the acquired image. |
- Exceptions
-
vpFrameGrabberException::initializationError | If the |
initialization of the grabber was not done previously.
Definition at line 259 of file vpROSGrabber.cpp.
◆ acquire() [5/8]
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 230 of file vpROSGrabber.cpp.
◆ acquire() [6/8]
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 442 of file vpROSGrabber.cpp.
◆ acquire() [7/8]
void vpROSGrabber::acquire |
( |
vpImage< vpRGBa > & |
I, |
|
|
double & |
timestamp_second |
|
) |
| |
Grab a color image with timestamp
- Parameters
-
I | : Acquired color image. |
timestamp_second | : timestamp expressed in [s] of the acquired image. |
- Exceptions
-
vpFrameGrabberException::initializationError | If the initialization of the grabber was not done previously. |
Definition at line 335 of file vpROSGrabber.cpp.
◆ acquire() [8/8]
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 308 of file vpROSGrabber.cpp.
◆ acquireNoWait() [1/4]
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 428 of file vpROSGrabber.cpp.
◆ acquireNoWait() [2/4]
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 278 of file vpROSGrabber.cpp.
◆ acquireNoWait() [3/4]
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 458 of file vpROSGrabber.cpp.
◆ acquireNoWait() [4/4]
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 354 of file vpROSGrabber.cpp.
◆ close()
void vpROSGrabber::close |
( |
| ) |
|
◆ getCameraInfo()
bool vpROSGrabber::getCameraInfo |
( |
vpCameraParameters & |
cam | ) |
|
◆ getHeight() [1/2]
unsigned int vpROSGrabber::getHeight |
( |
| ) |
const |
Get the height of the image.
- Returns
- height of the image.
Definition at line 566 of file vpROSGrabber.cpp.
◆ getHeight() [2/2]
void vpROSGrabber::getHeight |
( |
unsigned int |
height | ) |
const |
Get the height of the image.
- Parameters
-
height | : height of the image. |
Definition at line 542 of file vpROSGrabber.cpp.
◆ getWidth() [1/2]
unsigned int vpROSGrabber::getWidth |
( |
| ) |
const |
Get the width of the image.
- Returns
- width of the image.
Definition at line 554 of file vpROSGrabber.cpp.
◆ getWidth() [2/2]
void vpROSGrabber::getWidth |
( |
unsigned int |
width | ) |
const |
Get the width of the image.
- Parameters
-
width | : width of the image. |
Definition at line 529 of file vpROSGrabber.cpp.
◆ imageCallback()
void vpROSGrabber::imageCallback |
( |
const sensor_msgs::CompressedImage::ConstPtr & |
msg | ) |
|
|
protected |
◆ imageCallbackRaw()
void vpROSGrabber::imageCallbackRaw |
( |
const sensor_msgs::Image::ConstPtr & |
msg | ) |
|
|
protected |
◆ open() [1/4]
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 155 of file vpROSGrabber.cpp.
◆ open() [2/4]
void vpROSGrabber::open |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
◆ open() [3/4]
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 196 of file vpROSGrabber.cpp.
◆ open() [4/4]
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 212 of file vpROSGrabber.cpp.
◆ paramCallback()
void vpROSGrabber::paramCallback |
( |
const sensor_msgs::CameraInfo::ConstPtr & |
msg | ) |
|
|
protected |
◆ setCameraInfoTopic()
void vpROSGrabber::setCameraInfoTopic |
( |
const std::string & |
topic_name | ) |
|
◆ setFlip()
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 503 of file vpROSGrabber.cpp.
◆ setImageTopic()
void vpROSGrabber::setImageTopic |
( |
const std::string & |
topic_name | ) |
|
◆ setImageTransport()
void vpROSGrabber::setImageTransport |
( |
const 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
-
Definition at line 636 of file vpROSGrabber.cpp.
◆ setMasterURI()
void vpROSGrabber::setMasterURI |
( |
const 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 605 of file vpROSGrabber.cpp.
◆ setNodespace()
void vpROSGrabber::setNodespace |
( |
const std::string & |
nodespace | ) |
|
Set the nodespace
- Parameters
-
nodespace | Namespace of the connected camera (nodespace is appended to the all topic names) |
Definition at line 618 of file vpROSGrabber.cpp.
◆ setRectify()
void vpROSGrabber::setRectify |
( |
bool |
rectify | ) |
|
◆ m_cam
vpCameraParameters vpROSGrabber::m_cam |
|
protected |
◆ m_cam_info_sub
◆ m_first_img_received
volatile bool vpROSGrabber::m_first_img_received |
|
protected |
◆ m_first_param_received
volatile bool vpROSGrabber::m_first_param_received |
|
protected |
◆ m_flip
bool vpROSGrabber::m_flip |
|
protected |
◆ m_height
volatile unsigned int vpROSGrabber::m_height |
|
protected |
◆ m_image_transport
std::string vpROSGrabber::m_image_transport |
|
protected |
◆ m_img
cv::Mat vpROSGrabber::m_img |
|
protected |
◆ m_img_sub
◆ m_isInitialized
volatile bool vpROSGrabber::m_isInitialized |
|
protected |
◆ m_master_uri
std::string vpROSGrabber::m_master_uri |
|
protected |
◆ m_mutex_image
volatile bool vpROSGrabber::m_mutex_image |
|
protected |
◆ m_mutex_param
volatile bool vpROSGrabber::m_mutex_param |
|
protected |
◆ m_n
◆ m_nodespace
std::string vpROSGrabber::m_nodespace |
|
protected |
◆ m_nsec
volatile uint32_t vpROSGrabber::m_nsec |
|
protected |
◆ m_p
◆ m_rectify
volatile bool vpROSGrabber::m_rectify |
|
protected |
◆ m_sec
volatile uint32_t vpROSGrabber::m_sec |
|
protected |
◆ m_spinner
◆ m_topic_cam_info
std::string vpROSGrabber::m_topic_cam_info |
|
protected |
◆ m_topic_image
std::string vpROSGrabber::m_topic_image |
|
protected |
◆ m_width
volatile unsigned int vpROSGrabber::m_width |
|
protected |
The documentation for this class was generated from the following files:
visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33