30 #ifndef PLANNER_CSPACE_PLANNER_3D_GRID_METRIC_CONVERTER_H 31 #define PLANNER_CSPACE_PLANNER_3D_GRID_METRIC_CONVERTER_H 33 #include <costmap_cspace_msgs/MapMetaData3D.h> 34 #include <nav_msgs/Path.h> 46 const costmap_cspace_msgs::MapMetaData3D& map_info,
47 const T x,
const T y,
const T yaw,
48 float& gx,
float& gy,
float& gyaw)
51 std::is_same<float, T>() || std::is_same<int, T>(),
"T must be float or int");
53 gx = (x + 0.5) * map_info.linear_resolution + map_info.origin.position.x;
54 gy = (y + 0.5) * map_info.linear_resolution + map_info.origin.position.y;
55 gyaw = yaw * map_info.angular_resolution;
58 const costmap_cspace_msgs::MapMetaData3D& map_info,
59 int& x,
int& y,
int& yaw,
60 const float gx,
const float gy,
const float gyaw)
62 x =
static_cast<int>(floor((gx - map_info.origin.position.x) / map_info.linear_resolution));
63 y =
static_cast<int>(floor((gy - map_info.origin.position.y) / map_info.linear_resolution));
64 yaw = lroundf(gyaw / map_info.angular_resolution);
67 template <
template <
class,
class>
class STL_CONTAINER = std::list>
69 const costmap_cspace_msgs::MapMetaData3D& map_info,
74 for (
const auto& p : path_grid)
78 geometry_msgs::PoseStamped ps;
79 ps.header = path.header;
81 ps.pose.position.x = x;
82 ps.pose.position.y = y;
83 ps.pose.position.z = 0;
86 path.poses.push_back(ps);
91 #endif // PLANNER_CSPACE_PLANNER_3D_GRID_METRIC_CONVERTER_H TFSIMD_FORCE_INLINE const tfScalar & y() const
void metric2Grid(const costmap_cspace_msgs::MapMetaData3D &map_info, int &x, int &y, int &yaw, const float gx, const float gy, const float gyaw)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void grid2Metric(const costmap_cspace_msgs::MapMetaData3D &map_info, const T x, const T y, const T yaw, float &gx, float &gy, float &gyaw)
void grid2MetricPath(const costmap_cspace_msgs::MapMetaData3D &map_info, const STL_CONTAINER< CyclicVecFloat< 3, 2 >, std::allocator< CyclicVecFloat< 3, 2 >>> &path_grid, nav_msgs::Path &path)