16 #ifndef NAV2_SMAC_PLANNER__UTILS_HPP_
17 #define NAV2_SMAC_PLANNER__UTILS_HPP_
23 #include "nlohmann/json.hpp"
24 #include "geometry_msgs/msg/quaternion.hpp"
25 #include "geometry_msgs/msg/pose.hpp"
26 #include "tf2/utils.hpp"
27 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
28 #include "nav2_costmap_2d/inflation_layer.hpp"
29 #include "visualization_msgs/msg/marker_array.hpp"
30 #include "nav2_smac_planner/types.hpp"
31 #include <rclcpp/rclcpp.hpp>
33 namespace nav2_smac_planner
43 inline geometry_msgs::msg::Pose getWorldCoords(
46 geometry_msgs::msg::Pose msg;
59 inline geometry_msgs::msg::Quaternion getWorldOrientation(
64 q.setEuler(0.0, 0.0, theta);
75 inline double findCircumscribedCost(std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap)
78 std::vector<std::shared_ptr<nav2_costmap_2d::Layer>>::iterator layer;
81 const auto inflation_layer = nav2_costmap_2d::InflationLayer::getInflationLayer(costmap);
82 if (inflation_layer !=
nullptr) {
83 double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius();
84 double resolution = costmap->getCostmap()->getResolution();
85 double inflation_radius = inflation_layer->getInflationRadius();
86 if (inflation_radius < circum_radius) {
88 rclcpp::get_logger(
"computeCircumscribedCost"),
89 "The inflation radius (%f) is smaller than the circumscribed radius (%f) "
90 "If this is an SE2-collision checking plugin, it cannot use costmap potential "
91 "field to speed up collision checking by only checking the full footprint "
92 "when robot is within possibly-inscribed radius of an obstacle. This may "
93 "significantly slow down planning times!",
94 inflation_radius, circum_radius);
98 result =
static_cast<double>(inflation_layer->computeCost(circum_radius / resolution));
101 rclcpp::get_logger(
"computeCircumscribedCost"),
102 "No inflation layer found in costmap configuration. "
103 "If this is an SE2-collision checking plugin, it cannot use costmap potential "
104 "field to speed up collision checking by only checking the full footprint "
105 "when robot is within possibly-inscribed radius of an obstacle. This may "
106 "significantly slow down planning times!");
117 inline void fromJsonToMetaData(
const nlohmann::json & json, LatticeMetadata & lattice_metadata)
119 json.at(
"turning_radius").get_to(lattice_metadata.min_turning_radius);
120 json.at(
"grid_resolution").get_to(lattice_metadata.grid_resolution);
121 json.at(
"num_of_headings").get_to(lattice_metadata.number_of_headings);
122 json.at(
"heading_angles").get_to(lattice_metadata.heading_angles);
123 json.at(
"number_of_trajectories").get_to(lattice_metadata.number_of_trajectories);
124 json.at(
"motion_model").get_to(lattice_metadata.motion_model);
132 inline void fromJsonToPose(
const nlohmann::json & json, MotionPose & pose)
136 pose._theta = json[2];
144 inline void fromJsonToMotionPrimitive(
145 const nlohmann::json & json, MotionPrimitive & motion_primitive)
147 json.at(
"trajectory_id").get_to(motion_primitive.trajectory_id);
148 json.at(
"start_angle_index").get_to(motion_primitive.start_angle);
149 json.at(
"end_angle_index").get_to(motion_primitive.end_angle);
150 json.at(
"trajectory_radius").get_to(motion_primitive.turning_radius);
151 json.at(
"trajectory_length").get_to(motion_primitive.trajectory_length);
152 json.at(
"arc_length").get_to(motion_primitive.arc_length);
153 json.at(
"straight_length").get_to(motion_primitive.straight_length);
154 json.at(
"left_turn").get_to(motion_primitive.left_turn);
156 for (
unsigned int i = 0; i < json[
"poses"].size(); i++) {
158 fromJsonToPose(json[
"poses"][i], pose);
159 motion_primitive.poses.push_back(pose);
168 inline std::vector<geometry_msgs::msg::Point> transformFootprintToEdges(
169 const geometry_msgs::msg::Pose & pose,
170 const std::vector<geometry_msgs::msg::Point> & footprint)
172 const double & x = pose.position.x;
173 const double & y = pose.position.y;
174 const double & yaw = tf2::getYaw(pose.orientation);
175 const double sin_yaw = sin(yaw);
176 const double cos_yaw = cos(yaw);
178 std::vector<geometry_msgs::msg::Point> out_footprint;
179 out_footprint.resize(2 * footprint.size());
180 for (
unsigned int i = 0; i < footprint.size(); i++) {
181 out_footprint[2 * i].x = x + cos_yaw * footprint[i].x - sin_yaw * footprint[i].y;
182 out_footprint[2 * i].y = y + sin_yaw * footprint[i].x + cos_yaw * footprint[i].y;
184 out_footprint.back().x = out_footprint[i].x;
185 out_footprint.back().y = out_footprint[i].y;
187 out_footprint[2 * i - 1].x = out_footprint[2 * i].x;
188 out_footprint[2 * i - 1].y = out_footprint[2 * i].y;
191 return out_footprint;
202 inline visualization_msgs::msg::Marker createMarker(
203 const std::vector<geometry_msgs::msg::Point> edge,
204 unsigned int i,
const std::string & frame_id,
const rclcpp::Time & timestamp)
206 visualization_msgs::msg::Marker marker;
207 marker.header.frame_id = frame_id;
208 marker.header.stamp = timestamp;
209 marker.frame_locked =
false;
210 marker.ns =
"planned_footprint";
211 marker.action = visualization_msgs::msg::Marker::ADD;
212 marker.type = visualization_msgs::msg::Marker::LINE_LIST;
213 marker.lifetime = rclcpp::Duration(0, 0);
216 for (
auto & point : edge) {
217 marker.points.push_back(point);
220 marker.pose.orientation.x = 0.0;
221 marker.pose.orientation.y = 0.0;
222 marker.pose.orientation.z = 0.0;
223 marker.pose.orientation.w = 1.0;
224 marker.scale.x = 0.05;
225 marker.scale.y = 0.05;
226 marker.scale.z = 0.05;
227 marker.color.r = 0.0f;
228 marker.color.g = 0.0f;
229 marker.color.b = 1.0f;
230 marker.color.a = 1.3f;
A 2D costmap provides a mapping between points in the world and their associated "costs".
double getResolution() const
Accessor for the resolution of the costmap.
double getOriginY() const
Accessor for the y origin of the costmap.
double getOriginX() const
Accessor for the x origin of the costmap.