$search
#include <boost/optional.hpp>
#include <ros/ros.h>
#include <geometry_msgs/Transform.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
#include <tf/transform_datatypes.h>
#include <visp/vpHomogeneousMatrix.h>
#include <visp/vpCameraParameters.h>
#include <visp/vpMbEdgeTracker.h>
#include <visp/vpMe.h>
#include <visp_tracker/Init.h>
#include <visp_tracker/MovingEdgeConfig.h>
Go to the source code of this file.
Functions | |
void | convertInitRequestToVpMe (const visp_tracker::Init::Request &req, vpMbEdgeTracker &tracker, vpMe &moving_edge) |
void | convertMovingEdgeConfigToVpMe (const visp_tracker::MovingEdgeConfig &config, vpMe &moving_edge, vpMbEdgeTracker &tracker) |
void | convertVpMeToInitRequest (const vpMe &moving_edge, const vpMbEdgeTracker &tracker, visp_tracker::Init &srv) |
void | convertVpMeToMovingEdgeConfig (const vpMe &moving_edge, const vpMbEdgeTracker &tracker, visp_tracker::MovingEdgeConfig &config) |
void | initializeVpCameraFromCameraInfo (vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info) |
void | rosImageToVisp (vpImage< unsigned char > &dst, const sensor_msgs::Image::ConstPtr &src) |
Convert a ROS image into a ViSP one. | |
void | transformToVpHomogeneousMatrix (vpHomogeneousMatrix &dst, const geometry_msgs::Pose &src) |
void | transformToVpHomogeneousMatrix (vpHomogeneousMatrix &dst, const tf::Transform &src) |
void | transformToVpHomogeneousMatrix (vpHomogeneousMatrix &dst, const geometry_msgs::Transform &src) |
void | vispImageToRos (sensor_msgs::Image &dst, const vpImage< unsigned char > &src) |
Convert a ViSP image into a ROS one. | |
void | vpHomogeneousMatrixToTransform (geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src) |
void convertInitRequestToVpMe | ( | const visp_tracker::Init::Request & | req, | |
vpMbEdgeTracker & | tracker, | |||
vpMe & | moving_edge | |||
) |
Definition at line 221 of file conversion.cpp.
void convertMovingEdgeConfigToVpMe | ( | const visp_tracker::MovingEdgeConfig & | config, | |
vpMe & | moving_edge, | |||
vpMbEdgeTracker & | tracker | |||
) |
Definition at line 155 of file conversion.cpp.
void convertVpMeToInitRequest | ( | const vpMe & | moving_edge, | |
const vpMbEdgeTracker & | tracker, | |||
visp_tracker::Init & | srv | |||
) |
Definition at line 199 of file conversion.cpp.
void convertVpMeToMovingEdgeConfig | ( | const vpMe & | moving_edge, | |
const vpMbEdgeTracker & | tracker, | |||
visp_tracker::MovingEdgeConfig & | config | |||
) |
Definition at line 177 of file conversion.cpp.
void initializeVpCameraFromCameraInfo | ( | vpCameraParameters & | cam, | |
sensor_msgs::CameraInfoConstPtr | info | |||
) |
Definition at line 243 of file conversion.cpp.
void rosImageToVisp | ( | vpImage< unsigned char > & | dst, | |
const sensor_msgs::Image::ConstPtr & | src | |||
) |
Convert a ROS image into a ViSP one.
This function copy a ROS image into a ViSP image. If the size are not matching, the ViSP image will be resized.
dst | ViSP destination image | |
src | ROS source image |
Definition at line 22 of file conversion.cpp.
void transformToVpHomogeneousMatrix | ( | vpHomogeneousMatrix & | dst, | |
const geometry_msgs::Pose & | src | |||
) |
Definition at line 122 of file conversion.cpp.
void transformToVpHomogeneousMatrix | ( | vpHomogeneousMatrix & | dst, | |
const tf::Transform & | src | |||
) |
Definition at line 141 of file conversion.cpp.
void transformToVpHomogeneousMatrix | ( | vpHomogeneousMatrix & | dst, | |
const geometry_msgs::Transform & | src | |||
) |
Definition at line 104 of file conversion.cpp.
void vispImageToRos | ( | sensor_msgs::Image & | dst, | |
const vpImage< unsigned char > & | src | |||
) |
Convert a ViSP image into a ROS one.
This function copy a ViSP image into a ROS image. The whole content of the ROS image will be reset except the following field which will not be set:
dst | ROS destination image | |
src | ViSP source image |
Definition at line 71 of file conversion.cpp.
void vpHomogeneousMatrixToTransform | ( | geometry_msgs::Transform & | dst, | |
const vpHomogeneousMatrix & | src | |||
) |
Definition at line 84 of file conversion.cpp.