Functions
visp_bridge Namespace Reference

Functions

geometry_msgs::Pose toGeometryMsgsPose (vpHomogeneousMatrix &mat)
 Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Pose.
geometry_msgs::Transform toGeometryMsgsTransform (vpHomogeneousMatrix &mat)
 Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Transform.
sensor_msgs::CameraInfo toSensorMsgsCameraInfo (vpCameraParameters &cam_info, unsigned int cam_image_width, unsigned int cam_image_height)
 Converts ViSP camera parameters (vpCameraParameters) to sensor_msgs::CameraInfo.
sensor_msgs::Image toSensorMsgsImage (const vpImage< unsigned char > &src)
 Converts a ViSP image (vpImage) to a sensor_msgs::Image. Only works for greyscale images.
sensor_msgs::Image toSensorMsgsImage (const vpImage< vpRGBa > &src)
vpCameraParameters toVispCameraParameters (const sensor_msgs::CameraInfo &cam_info)
 Converts a sensor_msgs::CameraInfo to ViSP camera parameters (vpCameraParameters).
vpHomogeneousMatrix toVispHomogeneousMatrix (const geometry_msgs::Transform &trans)
 Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).
vpHomogeneousMatrix toVispHomogeneousMatrix (const geometry_msgs::Pose &pose)
 Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).
vpImage< unsigned char > toVispImage (const sensor_msgs::Image &src)
 Converts a sensor_msgs::Image to a ViSP image (vpImage). Only works for greyscale images.
vpImage< vpRGBa > toVispImageRGBa (const sensor_msgs::Image &src)

Function Documentation

geometry_msgs::Pose visp_bridge::toGeometryMsgsPose ( vpHomogeneousMatrix &  mat)

Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Pose.

Parameters:
mat,:transformation in ViSP format.
Returns:
: transformation in ROS/geometry_msgs format.
geometry_msgs::Transform visp_bridge::toGeometryMsgsTransform ( vpHomogeneousMatrix &  mat)

Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Transform.

Parameters:
mat,:transformation in ViSP format.
Returns:
: transformation in ROS/geometry_msgs format.

Definition at line 152 of file 3dpose.cpp.

sensor_msgs::CameraInfo visp_bridge::toSensorMsgsCameraInfo ( vpCameraParameters &  cam_info,
unsigned int  cam_image_width,
unsigned int  cam_image_height 
)

Converts ViSP camera parameters (vpCameraParameters) to sensor_msgs::CameraInfo.

Parameters:
cam_info,:camera parameters in ViSP format.
cam_image_width,:x-resolution of the camera image
cam_image_height,:y-resolution of the camera image
Returns:
: camera parameters in ROS/sensor_msgs format.

Definition at line 93 of file camera.cpp.

sensor_msgs::Image visp_bridge::toSensorMsgsImage ( const vpImage< unsigned char > &  src)

Converts a ViSP image (vpImage) to a sensor_msgs::Image. Only works for greyscale images.

Parameters:
src,:image in ViSP format.
Returns:
: image in ROS/sensor_msgs format.

Definition at line 59 of file image.cpp.

sensor_msgs::Image visp_bridge::toSensorMsgsImage ( const vpImage< vpRGBa > &  src)

Definition at line 131 of file image.cpp.

vpCameraParameters visp_bridge::toVispCameraParameters ( const sensor_msgs::CameraInfo &  cam_info)

Converts a sensor_msgs::CameraInfo to ViSP camera parameters (vpCameraParameters).

Parameters:
cam_info,:camera parameters in ROS/sensor_msgs format.
Returns:
: camera parameters in ViSP format.

Definition at line 56 of file camera.cpp.

vpHomogeneousMatrix visp_bridge::toVispHomogeneousMatrix ( const geometry_msgs::Transform &  trans)

Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).

Parameters:
trans,:transformation in ROS/geometry_msgs format.
Returns:
: transformation in ViSP format.

Definition at line 126 of file 3dpose.cpp.

vpHomogeneousMatrix visp_bridge::toVispHomogeneousMatrix ( const geometry_msgs::Pose pose)

Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).

Parameters:
pose,:transformation in ROS/geometry_msgs format.
Returns:
: transformation in ViSP format.

Definition at line 171 of file 3dpose.cpp.

vpImage< unsigned char > visp_bridge::toVispImage ( const sensor_msgs::Image &  src)

Converts a sensor_msgs::Image to a ViSP image (vpImage). Only works for greyscale images.

Parameters:
src,:image in ROS/sensor_msgs format.
Returns:
: image in ViSP format.

Definition at line 72 of file image.cpp.

vpImage< vpRGBa > visp_bridge::toVispImageRGBa ( const sensor_msgs::Image &  src)

Definition at line 101 of file image.cpp.



visp_bridge
Author(s): Filip Novotny
autogenerated on Sat Dec 28 2013 17:45:37