Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
vpROSGrabber Class Reference

Class for cameras video capture for ROS cameras. More...

#include <vpROSGrabber.h>

Inheritance diagram for vpROSGrabber:
Inheritance graph
[legend]

Public Member Functions

cv::Mat acquire ()
 
cv::Mat acquire (struct timespec &timestamp)
 
void acquire (vpImage< unsigned char > &I)
 
void acquire (vpImage< unsigned char > &I, double &timestamp_second)
 
void acquire (vpImage< unsigned char > &I, struct timespec &timestamp)
 
void acquire (vpImage< vpRGBa > &I)
 
void acquire (vpImage< vpRGBa > &I, double &timestamp_second)
 
void acquire (vpImage< vpRGBa > &I, struct timespec &timestamp)
 
bool acquireNoWait (vpImage< unsigned char > &I)
 
bool acquireNoWait (vpImage< unsigned char > &I, struct timespec &timestamp)
 
bool acquireNoWait (vpImage< vpRGBa > &I)
 
bool acquireNoWait (vpImage< vpRGBa > &I, struct timespec &timestamp)
 
void close ()
 
bool getCameraInfo (vpCameraParameters &cam)
 
unsigned int getHeight () const
 
void getHeight (unsigned int height) const
 
unsigned int getWidth () const
 
void getWidth (unsigned int width) const
 
void open ()
 
void open (int argc, char **argv)
 
void open (vpImage< unsigned char > &I)
 
void open (vpImage< vpRGBa > &I)
 
void setCameraInfoTopic (const std::string &topic_name)
 
void setFlip (bool flipType)
 
void setImageTopic (const std::string &topic_name)
 
void setImageTransport (const std::string &image_transport)
 
void setMasterURI (const std::string &master_uri)
 
void setNodespace (const 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 m_cam
 
ros::Subscriber m_cam_info_sub
 
volatile bool m_first_img_received
 
volatile bool m_first_param_received
 
bool m_flip
 
volatile unsigned int m_height
 
std::string m_image_transport
 
cv::Mat m_img
 
ros::Subscriber m_img_sub
 
volatile bool m_isInitialized
 
std::string m_master_uri
 
volatile bool m_mutex_image
 
volatile bool m_mutex_param
 
ros::NodeHandlem_n
 
std::string m_nodespace
 
volatile uint32_t m_nsec
 
image_geometry::PinholeCameraModel m_p
 
volatile bool m_rectify
 
volatile uint32_t m_sec
 
ros::AsyncSpinnerm_spinner
 
std::string m_topic_cam_info
 
std::string m_topic_image
 
volatile unsigned int m_width
 

Detailed Description

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>
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
}
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.

Constructor & Destructor Documentation

◆ 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

Basic destructor that calls the close() method.

See also
close()

Definition at line 84 of file vpROSGrabber.cpp.

Member Function Documentation

◆ acquire() [1/8]

cv::Mat vpROSGrabber::acquire ( )

Grab an image direclty in the OpenCV format.

Returns
Acquired image.
Exceptions
vpFrameGrabberException::initializationErrorIf 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::initializationErrorIf 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)

Grab a gray level image

Parameters
I: Acquired gray level image.
Exceptions
vpFrameGrabberException::initializationErrorIf the initialization of the grabber was not done previously.
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 412 of file vpROSGrabber.cpp.

◆ 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::initializationErrorIf 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::initializationErrorIf 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
I: Acquired color image.
Exceptions
vpFrameGrabberException::initializationErrorIf 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::initializationErrorIf 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::initializationErrorIf 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::initializationErrorIf 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::initializationErrorIf 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
I: Acquired color image.
Returns
true if a new image was acquired or false if the image is the same than the previous one.
Exceptions
vpFrameGrabberException::initializationErrorIf 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::initializationErrorIf the initialization of the grabber was not done previously.

Definition at line 354 of file vpROSGrabber.cpp.

◆ close()

void vpROSGrabber::close ( )

Definition at line 480 of file vpROSGrabber.cpp.

◆ getCameraInfo()

bool vpROSGrabber::getCameraInfo ( vpCameraParameters &  cam)

Get the vpCameraParameters from the camera.

Parameters
cam: Parameter of the camera.
Returns
true if the parameters are available, false otherwise.
Examples
tutorial-franka-coppeliasim-dual-arm.cpp, tutorial-franka-coppeliasim-ibvs-apriltag.cpp, tutorial-franka-coppeliasim-pbvs-apriltag.cpp, tutorial-ros-pioneer-visual-servo.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 649 of file vpROSGrabber.cpp.

◆ 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

Definition at line 671 of file vpROSGrabber.cpp.

◆ imageCallbackRaw()

void vpROSGrabber::imageCallbackRaw ( const sensor_msgs::Image::ConstPtr &  msg)
protected

Definition at line 696 of file vpROSGrabber.cpp.

◆ open() [1/4]

void vpROSGrabber::open ( )

Initialization of the grabber.

Generic initialization of the grabber.

Exceptions
vpFrameGrabberException::initializationErrorIf 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 
)

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

Parameters
argc: number of arguments from the main function
argv: arguments from the main function
Examples
tutorial-franka-coppeliasim-dual-arm.cpp, tutorial-franka-coppeliasim-ibvs-apriltag.cpp, tutorial-franka-coppeliasim-pbvs-apriltag.cpp, tutorial-ros-grabber.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 98 of file vpROSGrabber.cpp.

◆ 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

Definition at line 729 of file vpROSGrabber.cpp.

◆ 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
image_transporttype of transport of the image topic

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
nodespaceNamespace 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)

Set the boolean variable rectify to the expected value.

Parameters
rectify: Expected value of the variable rectify. True means that the image is rectified during each image acquisition.
Warning
Rectification will happen only if the CameraInfo are correctly received.
Examples
tutorial-ros-grabber.cpp, tutorial-ros-pioneer-visual-servo.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 517 of file vpROSGrabber.cpp.

Member Data Documentation

◆ m_cam

vpCameraParameters vpROSGrabber::m_cam
protected

Definition at line 130 of file vpROSGrabber.h.

◆ m_cam_info_sub

ros::Subscriber vpROSGrabber::m_cam_info_sub
protected

Definition at line 109 of file vpROSGrabber.h.

◆ m_first_img_received

volatile bool vpROSGrabber::m_first_img_received
protected

Definition at line 122 of file vpROSGrabber.h.

◆ m_first_param_received

volatile bool vpROSGrabber::m_first_param_received
protected

Definition at line 123 of file vpROSGrabber.h.

◆ m_flip

bool vpROSGrabber::m_flip
protected

Definition at line 116 of file vpROSGrabber.h.

◆ m_height

volatile unsigned int vpROSGrabber::m_height
protected

Definition at line 113 of file vpROSGrabber.h.

◆ m_image_transport

std::string vpROSGrabber::m_image_transport
protected

Definition at line 129 of file vpROSGrabber.h.

◆ m_img

cv::Mat vpROSGrabber::m_img
protected

Definition at line 115 of file vpROSGrabber.h.

◆ m_img_sub

ros::Subscriber vpROSGrabber::m_img_sub
protected

Definition at line 108 of file vpROSGrabber.h.

◆ m_isInitialized

volatile bool vpROSGrabber::m_isInitialized
protected

Definition at line 111 of file vpROSGrabber.h.

◆ m_master_uri

std::string vpROSGrabber::m_master_uri
protected

Definition at line 125 of file vpROSGrabber.h.

◆ m_mutex_image

volatile bool vpROSGrabber::m_mutex_image
protected

Definition at line 118 of file vpROSGrabber.h.

◆ m_mutex_param

volatile bool vpROSGrabber::m_mutex_param
protected

Definition at line 118 of file vpROSGrabber.h.

◆ m_n

ros::NodeHandle* vpROSGrabber::m_n
protected

Definition at line 107 of file vpROSGrabber.h.

◆ m_nodespace

std::string vpROSGrabber::m_nodespace
protected

Definition at line 128 of file vpROSGrabber.h.

◆ m_nsec

volatile uint32_t vpROSGrabber::m_nsec
protected

Definition at line 124 of file vpROSGrabber.h.

◆ m_p

image_geometry::PinholeCameraModel vpROSGrabber::m_p
protected

Definition at line 114 of file vpROSGrabber.h.

◆ m_rectify

volatile bool vpROSGrabber::m_rectify
protected

Definition at line 117 of file vpROSGrabber.h.

◆ m_sec

volatile uint32_t vpROSGrabber::m_sec
protected

Definition at line 124 of file vpROSGrabber.h.

◆ m_spinner

ros::AsyncSpinner* vpROSGrabber::m_spinner
protected

Definition at line 110 of file vpROSGrabber.h.

◆ m_topic_cam_info

std::string vpROSGrabber::m_topic_cam_info
protected

Definition at line 127 of file vpROSGrabber.h.

◆ m_topic_image

std::string vpROSGrabber::m_topic_image
protected

Definition at line 126 of file vpROSGrabber.h.

◆ m_width

volatile unsigned int vpROSGrabber::m_width
protected

Definition at line 112 of file vpROSGrabber.h.


The documentation for this class was generated from the following files:
vpROSGrabber
Class for cameras video capture for ROS cameras.
Definition: vpROSGrabber.h:104
main
int main(int argc, char **argv)
Definition: afma6.cpp:187
vpROSGrabber::open
void open(int argc, char **argv)
Definition: vpROSGrabber.cpp:98
vpROSGrabber::setImageTopic
void setImageTopic(const std::string &topic_name)
Definition: vpROSGrabber.cpp:592
vpROSGrabber::setCameraInfoTopic
void setCameraInfoTopic(const std::string &topic_name)
Definition: vpROSGrabber.cpp:579
vpROSGrabber::acquire
void acquire(vpImage< unsigned char > &I)
Definition: vpROSGrabber.cpp:412
vpROSGrabber::setRectify
void setRectify(bool rectify)
Definition: vpROSGrabber.cpp:517
vpROSGrabber.h
class for Camera video capture for ROS middleware.


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33