conversions.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV_2D_UTILS_CONVERSIONS_H
36 #define NAV_2D_UTILS_CONVERSIONS_H
37 
38 #include <ros/ros.h>
39 #include <geometry_msgs/Point.h>
40 #include <geometry_msgs/Pose.h>
41 #include <geometry_msgs/Twist.h>
42 #include <geometry_msgs/PolygonStamped.h>
43 #include <nav_2d_msgs/Twist2D.h>
44 #include <nav_2d_msgs/Path2D.h>
45 #include <nav_2d_msgs/Point2D.h>
46 #include <nav_2d_msgs/Polygon2D.h>
47 #include <nav_2d_msgs/Polygon2DStamped.h>
48 #include <nav_2d_msgs/Pose2DStamped.h>
49 #include <nav_2d_msgs/NavGridInfo.h>
50 #include <nav_2d_msgs/UIntBounds.h>
51 #include <nav_msgs/MapMetaData.h>
52 #include <nav_msgs/Path.h>
53 #include <nav_grid/nav_grid.h>
54 #include <nav_core2/bounds.h>
55 #include <tf/tf.h>
56 #include <vector>
57 #include <string>
58 
59 namespace nav_2d_utils
60 {
61 // Twist Transformations
62 geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D& cmd_vel_2d);
63 nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist& cmd_vel);
64 
65 // Point Transformations
66 nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point& point);
67 nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point32& point);
68 geometry_msgs::Point pointToPoint3D(const nav_2d_msgs::Point2D& point);
69 geometry_msgs::Point32 pointToPoint32(const nav_2d_msgs::Point2D& point);
70 
71 // Pose Transformations
72 nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped<tf::Pose>& pose);
73 nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped& pose);
74 geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D& pose2d);
75 geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped& pose2d);
76 geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D& pose2d,
77  const std::string& frame, const ros::Time& stamp);
78 
79 // Path Transformations
80 nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path& path);
81 nav_msgs::Path posesToPath(const std::vector<geometry_msgs::PoseStamped>& poses);
82 nav_2d_msgs::Path2D posesToPath2D(const std::vector<geometry_msgs::PoseStamped>& poses);
83 nav_msgs::Path poses2DToPath(const std::vector<geometry_msgs::Pose2D>& poses,
84  const std::string& frame, const ros::Time& stamp);
85 nav_msgs::Path pathToPath(const nav_2d_msgs::Path2D& path2d);
86 
87 // Polygon Transformations
88 geometry_msgs::Polygon polygon2Dto3D(const nav_2d_msgs::Polygon2D& polygon_2d);
89 nav_2d_msgs::Polygon2D polygon3Dto2D(const geometry_msgs::Polygon& polygon_3d);
90 geometry_msgs::PolygonStamped polygon2Dto3D(const nav_2d_msgs::Polygon2DStamped& polygon_2d);
91 nav_2d_msgs::Polygon2DStamped polygon3Dto2D(const geometry_msgs::PolygonStamped& polygon_3d);
92 
93 // Info Transformations
94 nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo& info);
95 nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo& msg);
96 geometry_msgs::Pose getOrigin3D(const nav_grid::NavGridInfo& info);
97 geometry_msgs::Pose2D getOrigin2D(const nav_grid::NavGridInfo& info);
98 nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData& metadata, const std::string& frame);
99 nav_msgs::MapMetaData infoToInfo(const nav_grid::NavGridInfo & info);
100 
101 // Bounds Transformations
102 nav_2d_msgs::UIntBounds toMsg(const nav_core2::UIntBounds& bounds);
103 nav_core2::UIntBounds fromMsg(const nav_2d_msgs::UIntBounds& msg);
104 
105 } // namespace nav_2d_utils
106 
107 #endif // NAV_2D_UTILS_CONVERSIONS_H
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata, const std::string &frame)
geometry_msgs::Point32 pointToPoint32(const nav_2d_msgs::Point2D &point)
Definition: conversions.cpp:84
geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D &pose2d)
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo &info)
nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path &path)
geometry_msgs::Point pointToPoint3D(const nav_2d_msgs::Point2D &point)
Definition: conversions.cpp:76
nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo &msg)
geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D &cmd_vel_2d)
Definition: conversions.cpp:41
nav_msgs::Path posesToPath(const std::vector< geometry_msgs::PoseStamped > &poses)
nav_2d_msgs::Path2D posesToPath2D(const std::vector< geometry_msgs::PoseStamped > &poses)
nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point &point)
Definition: conversions.cpp:60
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
nav_msgs::Path poses2DToPath(const std::vector< geometry_msgs::Pose2D > &poses, const std::string &frame, const ros::Time &stamp)
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
geometry_msgs::Pose getOrigin3D(const nav_grid::NavGridInfo &info)
nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped< tf::Pose > &pose)
Definition: conversions.cpp:92
geometry_msgs::Pose2D getOrigin2D(const nav_grid::NavGridInfo &info)
geometry_msgs::Polygon polygon2Dto3D(const nav_2d_msgs::Polygon2D &polygon_2d)
nav_2d_msgs::Polygon2D polygon3Dto2D(const geometry_msgs::Polygon &polygon_3d)
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)
Definition: conversions.cpp:51


nav_2d_utils
Author(s):
autogenerated on Sun Jan 10 2021 04:08:32