| Functions | |
| geometry_msgs::Pose | toGeometryMsgsPose (const vpHomogeneousMatrix &mat) | 
| Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Pose.  More... | |
| geometry_msgs::Transform | toGeometryMsgsTransform (const vpHomogeneousMatrix &mat) | 
| Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Transform.  More... | |
| geometry_msgs::Transform | toGeometryMsgsTransform (vpHomogeneousMatrix &mat) | 
| 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.  More... | |
| sensor_msgs::Image | toSensorMsgsImage (const vpImage< unsigned char > &src) | 
| Converts a ViSP image (vpImage) to a sensor_msgs::Image. Only works for greyscale images.  More... | |
| 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).  More... | |
| vpHomogeneousMatrix | toVispHomogeneousMatrix (const geometry_msgs::Pose &pose) | 
| Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).  More... | |
| vpHomogeneousMatrix | toVispHomogeneousMatrix (const geometry_msgs::Transform &trans) | 
| Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).  More... | |
| vpImage< unsigned char > | toVispImage (const sensor_msgs::Image &src) | 
| Converts a sensor_msgs::Image to a ViSP image (vpImage). Only works for greyscale images.  More... | |
| vpImage< vpRGBa > | toVispImageRGBa (const sensor_msgs::Image &src) | 
| geometry_msgs::Pose visp_bridge::toGeometryMsgsPose | ( | const vpHomogeneousMatrix & | mat | ) | 
Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Pose.
| mat | transformation in ViSP format. | 
| geometry_msgs::Transform visp_bridge::toGeometryMsgsTransform | ( | const vpHomogeneousMatrix & | mat | ) | 
Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Transform.
| mat | transformation in ViSP format. | 
| geometry_msgs::Transform visp_bridge::toGeometryMsgsTransform | ( | vpHomogeneousMatrix & | mat | ) | 
Definition at line 167 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.
| 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 | 
Definition at line 94 of file camera.cpp.
| sensor_msgs::Image visp_bridge::toSensorMsgsImage | ( | const vpImage< unsigned char > & | src | ) | 
| sensor_msgs::Image visp_bridge::toSensorMsgsImage | ( | const vpImage< vpRGBa > & | src | ) | 
| vpCameraParameters visp_bridge::toVispCameraParameters | ( | const sensor_msgs::CameraInfo & | cam_info | ) | 
Converts a sensor_msgs::CameraInfo to ViSP camera parameters (vpCameraParameters).
| cam_info | camera parameters in ROS/sensor_msgs format. | 
Definition at line 56 of file camera.cpp.
| vpHomogeneousMatrix visp_bridge::toVispHomogeneousMatrix | ( | const geometry_msgs::Pose & | pose | ) | 
Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).
| pose | transformation in ROS/geometry_msgs format. | 
Definition at line 186 of file 3dpose.cpp.
| vpHomogeneousMatrix visp_bridge::toVispHomogeneousMatrix | ( | const geometry_msgs::Transform & | trans | ) | 
Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).
| trans | transformation in ROS/geometry_msgs format. | 
Definition at line 137 of file 3dpose.cpp.
| vpImage< unsigned char > visp_bridge::toVispImage | ( | const sensor_msgs::Image & | src | ) |