#include <cstring>
#include <stdexcept>
#include <boost/format.hpp>
#include <tf/transform_datatypes.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <sensor_msgs/distortion_models.h>
#include <visp/vpImage.h>
#include <visp/vpTranslationVector.h>
#include <visp/vpQuaternionVector.h>
#include <visp/vpMbEdgeTracker.h>
#include <visp/vpMbKltTracker.h>
#include "conversion.hh"
Go to the source code of this file.
Functions | |
void | convertInitRequestToVpKltOpencv (const visp_tracker::Init::Request &req, vpMbTracker *tracker, vpKltOpencv &klt) |
void | convertInitRequestToVpMbTracker (const visp_tracker::Init::Request &req, vpMbTracker *tracker) |
void | convertInitRequestToVpMe (const visp_tracker::Init::Request &req, vpMbTracker *tracker, vpMe &moving_edge) |
void | convertVpKltOpencvToInitRequest (const vpKltOpencv &klt, const vpMbTracker *tracker, visp_tracker::Init &srv) |
std::string | convertVpKltOpencvToRosMessage (const vpMbTracker *tracker, const vpKltOpencv &klt) |
void | convertVpMbTrackerToInitRequest (const vpMbTracker *tracker, visp_tracker::Init &srv) |
std::string | convertVpMbTrackerToRosMessage (const vpMbTracker *tracker) |
void | convertVpMeToInitRequest (const vpMe &moving_edge, const vpMbTracker *tracker, visp_tracker::Init &srv) |
std::string | convertVpMeToRosMessage (const vpMbTracker *tracker, const vpMe &moving_edge) |
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::Transform &src) |
void | transformToVpHomogeneousMatrix (vpHomogeneousMatrix &dst, const geometry_msgs::Pose &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 convertInitRequestToVpKltOpencv | ( | const visp_tracker::Init::Request & | req, |
vpMbTracker * | tracker, | ||
vpKltOpencv & | klt | ||
) |
Definition at line 330 of file conversion.cpp.
void convertInitRequestToVpMbTracker | ( | const visp_tracker::Init::Request & | req, |
vpMbTracker * | tracker | ||
) |
Definition at line 232 of file conversion.cpp.
void convertInitRequestToVpMe | ( | const visp_tracker::Init::Request & | req, |
vpMbTracker * | tracker, | ||
vpMe & | moving_edge | ||
) |
Definition at line 282 of file conversion.cpp.
void convertVpKltOpencvToInitRequest | ( | const vpKltOpencv & | klt, |
const vpMbTracker * | tracker, | ||
visp_tracker::Init & | srv | ||
) |
Definition at line 314 of file conversion.cpp.
std::string convertVpKltOpencvToRosMessage | ( | const vpMbTracker * | tracker, |
const vpKltOpencv & | klt | ||
) |
Definition at line 134 of file conversion.cpp.
void convertVpMbTrackerToInitRequest | ( | const vpMbTracker * | tracker, |
visp_tracker::Init & | srv | ||
) |
Definition at line 208 of file conversion.cpp.
std::string convertVpMbTrackerToRosMessage | ( | const vpMbTracker * | tracker | ) |
Definition at line 87 of file conversion.cpp.
void convertVpMeToInitRequest | ( | const vpMe & | moving_edge, |
const vpMbTracker * | tracker, | ||
visp_tracker::Init & | srv | ||
) |
Definition at line 254 of file conversion.cpp.
std::string convertVpMeToRosMessage | ( | const vpMbTracker * | tracker, |
const vpMe & | moving_edge | ||
) |
Definition at line 113 of file conversion.cpp.
void initializeVpCameraFromCameraInfo | ( | vpCameraParameters & | cam, |
sensor_msgs::CameraInfoConstPtr | info | ||
) |
Definition at line 348 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 27 of file conversion.cpp.
void transformToVpHomogeneousMatrix | ( | vpHomogeneousMatrix & | dst, |
const geometry_msgs::Transform & | src | ||
) |
Definition at line 167 of file conversion.cpp.
void transformToVpHomogeneousMatrix | ( | vpHomogeneousMatrix & | dst, |
const geometry_msgs::Pose & | src | ||
) |
Definition at line 175 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 73 of file conversion.cpp.
void vpHomogeneousMatrixToTransform | ( | geometry_msgs::Transform & | dst, |
const vpHomogeneousMatrix & | src | ||
) |
Definition at line 151 of file conversion.cpp.