#include <cstring>#include <stdexcept>#include <boost/format.hpp>#include <vector>#include <string>#include <boost/detail/workaround.hpp>#include <boost/config.hpp>#include <locale>#include <streambuf>#include <ostream>#include <iosfwd>#include <boost/format/detail/compat_workarounds.hpp>#include <boost/format/format_fwd.hpp>#include <boost/assert.hpp>#include <boost/optional.hpp>#include <boost/limits.hpp>#include <boost/utility/base_from_member.hpp>#include <boost/shared_ptr.hpp>#include <boost/format/internals_fwd.hpp>#include <boost/format/internals.hpp>#include <boost/format/alt_sstream.hpp>#include <boost/throw_exception.hpp>#include <boost/format/format_class.hpp>#include <algorithm>#include <boost/format/group.hpp>#include <boost/format/exceptions.hpp>#include "btVector3.h"#include "btQuaternion.h"#include "btQuadWord.h"#include <sensor_msgs/Image.h>#include <visp/vpImage.h>#include <visp/vpMbEdgeTracker.h>#include "conversion.hh"

Go to the source code of this file.
Defines | |
| #define | protected public |
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::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) |
| #define protected public |
Definition at line 15 of file conversion.cpp.
| void convertInitRequestToVpMe | ( | const visp_tracker::Init::Request & | req, | |
| vpMbEdgeTracker & | tracker, | |||
| vpMe & | moving_edge | |||
| ) |
Definition at line 187 of file conversion.cpp.
| void convertMovingEdgeConfigToVpMe | ( | const visp_tracker::MovingEdgeConfig & | config, | |
| vpMe & | moving_edge, | |||
| vpMbEdgeTracker & | tracker | |||
| ) |
Definition at line 121 of file conversion.cpp.
| void convertVpMeToInitRequest | ( | const vpMe & | moving_edge, | |
| const vpMbEdgeTracker & | tracker, | |||
| visp_tracker::Init & | srv | |||
| ) |
Definition at line 165 of file conversion.cpp.
| void convertVpMeToMovingEdgeConfig | ( | const vpMe & | moving_edge, | |
| const vpMbEdgeTracker & | tracker, | |||
| visp_tracker::MovingEdgeConfig & | config | |||
| ) |
Definition at line 143 of file conversion.cpp.
| void initializeVpCameraFromCameraInfo | ( | vpCameraParameters & | cam, | |
| sensor_msgs::CameraInfoConstPtr | info | |||
| ) |
Definition at line 209 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 21 of file conversion.cpp.
| void transformToVpHomogeneousMatrix | ( | vpHomogeneousMatrix & | dst, | |
| const geometry_msgs::Transform & | src | |||
| ) |
Definition at line 103 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 70 of file conversion.cpp.
| void vpHomogeneousMatrixToTransform | ( | geometry_msgs::Transform & | dst, | |
| const vpHomogeneousMatrix & | src | |||
| ) |
Definition at line 83 of file conversion.cpp.