25 #include "angles/angles.h"
27 #include "ompl/base/ScopedState.h"
28 #include "ompl/base/spaces/DubinsStateSpace.h"
29 #include "ompl/base/spaces/ReedsSheppStateSpace.h"
31 #include "nav2_smac_planner/node_lattice.hpp"
33 using namespace std::chrono;
35 namespace nav2_smac_planner
39 LatticeMotionTable NodeLattice::motion_table;
40 float NodeLattice::size_lookup = 25;
41 LookupTable NodeLattice::dist_heuristic_lookup_table;
49 void LatticeMotionTable::initMotionModel(
50 unsigned int & size_x_in,
54 change_penalty = search_info.change_penalty;
55 non_straight_penalty = search_info.non_straight_penalty;
56 cost_penalty = search_info.cost_penalty;
57 reverse_penalty = search_info.reverse_penalty;
58 travel_distance_reward = 1.0f - search_info.retrospective_penalty;
59 allow_reverse_expansion = search_info.allow_reverse_expansion;
60 rotation_penalty = search_info.rotation_penalty;
61 min_turning_radius = search_info.minimum_turning_radius;
63 if (current_lattice_filepath == search_info.lattice_filepath) {
66 current_lattice_filepath = search_info.lattice_filepath;
69 lattice_metadata = getLatticeMetadata(current_lattice_filepath);
70 std::ifstream latticeFile(current_lattice_filepath);
71 if (!latticeFile.is_open()) {
72 throw std::runtime_error(
"Could not open lattice file");
76 num_angle_quantization = lattice_metadata.number_of_headings;
79 if (!allow_reverse_expansion) {
80 state_space = std::make_shared<ompl::base::DubinsStateSpace>(
81 lattice_metadata.min_turning_radius);
82 motion_model = MotionModel::DUBIN;
84 state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
85 lattice_metadata.min_turning_radius);
86 motion_model = MotionModel::REEDS_SHEPP;
91 float prev_start_angle = 0.0;
92 std::vector<MotionPrimitive> primitives;
93 nlohmann::json json_primitives = json[
"primitives"];
94 for (
unsigned int i = 0; i < json_primitives.size(); ++i) {
96 fromJsonToMotionPrimitive(json_primitives[i], new_primitive);
98 if (prev_start_angle != new_primitive.start_angle) {
99 motion_primitives.push_back(primitives);
101 prev_start_angle = new_primitive.start_angle;
103 primitives.push_back(new_primitive);
105 motion_primitives.push_back(primitives);
108 trig_values.reserve(lattice_metadata.number_of_headings);
109 for (
unsigned int i = 0; i < lattice_metadata.heading_angles.size(); ++i) {
110 trig_values.emplace_back(
111 cos(lattice_metadata.heading_angles[i]),
112 sin(lattice_metadata.heading_angles[i]));
116 MotionPrimitivePtrs LatticeMotionTable::getMotionPrimitives(
118 unsigned int & direction_change_index)
120 MotionPrimitives & prims_at_heading = motion_primitives[node->pose.theta];
121 MotionPrimitivePtrs primitive_projection_list;
122 for (
unsigned int i = 0; i != prims_at_heading.size(); i++) {
123 primitive_projection_list.push_back(&prims_at_heading[i]);
127 direction_change_index =
static_cast<unsigned int>(primitive_projection_list.size());
129 if (allow_reverse_expansion) {
131 double reserve_heading = node->pose.theta - (num_angle_quantization / 2);
132 if (reserve_heading < 0) {
133 reserve_heading += num_angle_quantization;
135 if (reserve_heading > num_angle_quantization) {
136 reserve_heading -= num_angle_quantization;
139 MotionPrimitives & prims_at_reverse_heading = motion_primitives[reserve_heading];
140 for (
unsigned int i = 0; i != prims_at_reverse_heading.size(); i++) {
141 primitive_projection_list.push_back(&prims_at_reverse_heading[i]);
145 return primitive_projection_list;
148 LatticeMetadata LatticeMotionTable::getLatticeMetadata(
const std::string & lattice_filepath)
150 std::ifstream lattice_file(lattice_filepath);
151 if (!lattice_file.is_open()) {
152 throw std::runtime_error(
"Could not open lattice file!");
158 fromJsonToMetaData(j[
"lattice_metadata"], metadata);
162 unsigned int LatticeMotionTable::getClosestAngularBin(
const double & theta)
164 float min_dist = std::numeric_limits<float>::max();
165 unsigned int closest_idx = 0;
167 for (
unsigned int i = 0; i != lattice_metadata.heading_angles.size(); i++) {
168 dist = fabs(angles::shortest_angular_distance(theta, lattice_metadata.heading_angles[i]));
169 if (dist < min_dist) {
177 float & LatticeMotionTable::getAngleFromBin(
const unsigned int & bin_idx)
179 return lattice_metadata.heading_angles[bin_idx];
182 double LatticeMotionTable::getAngle(
const double & theta)
184 return getClosestAngularBin(theta);
187 NodeLattice::NodeLattice(
const uint64_t index)
189 pose(0.0f, 0.0f, 0.0f),
190 _cell_cost(std::numeric_limits<float>::quiet_NaN()),
191 _accumulated_cost(std::numeric_limits<float>::max()),
194 _motion_primitive(nullptr),
196 _is_node_valid(false)
208 _cell_cost = std::numeric_limits<float>::quiet_NaN();
209 _accumulated_cost = std::numeric_limits<float>::max();
210 _was_visited =
false;
214 _motion_primitive =
nullptr;
216 _is_node_valid =
false;
220 const bool & traverse_unknown,
226 if (!std::isnan(_cell_cost)) {
227 return _is_node_valid;
233 const double angle = std::fmod(motion_table.
getAngleFromBin(this->pose.theta),
234 2.0 * M_PI) / bin_size;
236 this->pose.x, this->pose.y, angle , traverse_unknown))
238 _is_node_valid =
false;
239 _cell_cost = collision_checker->
getCost();
244 float max_cell_cost = collision_checker->
getCost();
247 if (motion_primitive) {
248 const float & grid_resolution = motion_table.lattice_metadata.grid_resolution;
249 const float & resolution_diag_sq = 2.0 * grid_resolution * grid_resolution;
250 MotionPose last_pose(1e9, 1e9, 1e9, TurnDirection::UNKNOWN);
251 MotionPose pose_dist(0.0, 0.0, 0.0, TurnDirection::UNKNOWN);
255 initial_pose._x = this->pose.x - (motion_primitive->poses.back()._x / grid_resolution);
256 initial_pose._y = this->pose.y - (motion_primitive->poses.back()._y / grid_resolution);
257 initial_pose._theta = motion_table.
getAngleFromBin(motion_primitive->start_angle);
259 for (
auto it = motion_primitive->poses.begin(); it != motion_primitive->poses.end(); ++it) {
261 pose_dist = *it - last_pose;
263 if (pose_dist._x * pose_dist._x + pose_dist._y * pose_dist._y > resolution_diag_sq) {
266 prim_pose._x = initial_pose._x + (it->_x / grid_resolution);
267 prim_pose._y = initial_pose._y + (it->_y / grid_resolution);
271 prim_pose._theta = std::fmod(it->_theta + M_PI, 2.0 * M_PI);
273 prim_pose._theta = std::fmod(it->_theta, 2.0 * M_PI);
278 prim_pose._theta / bin_size ,
281 _is_node_valid =
false;
282 _cell_cost = std::max(max_cell_cost, collision_checker->
getCost());
285 max_cell_cost = std::max(max_cell_cost, collision_checker->
getCost());
290 _cell_cost = max_cell_cost;
291 _is_node_valid =
true;
292 return _is_node_valid;
297 const float normalized_cost = child->
getCost() / 252.0;
298 if (std::isnan(normalized_cost)) {
299 throw std::runtime_error(
300 "Node attempted to get traversal "
301 "cost without a known collision cost!");
307 const float prim_length =
308 transition_prim->trajectory_length / motion_table.lattice_metadata.grid_resolution;
309 if (prim ==
nullptr) {
314 if (transition_prim->trajectory_length < 1e-4) {
315 return motion_table.rotation_penalty * (1.0 + motion_table.cost_penalty * normalized_cost);
318 float travel_cost = 0.0;
319 float travel_cost_raw = prim_length *
320 (motion_table.travel_distance_reward + motion_table.cost_penalty * normalized_cost);
322 if (transition_prim->arc_length < 0.001) {
324 travel_cost = travel_cost_raw;
326 if (prim->left_turn == transition_prim->left_turn) {
328 travel_cost = travel_cost_raw * motion_table.non_straight_penalty;
331 travel_cost = travel_cost_raw *
332 (motion_table.non_straight_penalty + motion_table.change_penalty);
339 travel_cost *= motion_table.reverse_penalty;
347 const CoordinateVector & goals_coords)
352 node_coords, goals_coords[0], motion_table.cost_penalty);
353 float distance_heuristic = std::numeric_limits<float>::max();
354 for (
unsigned int i = 0; i < goals_coords.size(); i++) {
355 distance_heuristic = std::min(
359 return std::max(obstacle_heuristic, distance_heuristic);
363 const MotionModel & motion_model,
364 unsigned int & size_x,
369 if (motion_model != MotionModel::STATE_LATTICE) {
370 throw std::runtime_error(
371 "Invalid motion model for Lattice node. Please select"
372 " STATE_LATTICE and provide a valid lattice file.");
381 const float & obstacle_heuristic)
390 const TrigValues & trig_vals = motion_table.trig_values[goal_coords.theta];
391 const float cos_th = trig_vals.first;
392 const float sin_th = -trig_vals.second;
393 const float dx = node_coords.x - goal_coords.x;
394 const float dy = node_coords.y - goal_coords.y;
396 double dtheta_bin = node_coords.theta - goal_coords.theta;
397 if (dtheta_bin < 0) {
398 dtheta_bin += motion_table.num_angle_quantization;
400 if (dtheta_bin > motion_table.num_angle_quantization) {
401 dtheta_bin -= motion_table.num_angle_quantization;
405 round(dx * cos_th - dy * sin_th),
406 round(dx * sin_th + dy * cos_th),
412 float motion_heuristic = 0.0;
413 const int floored_size = floor(size_lookup / 2.0);
414 const int ceiling_size = ceil(size_lookup / 2.0);
415 const float mirrored_relative_y = abs(node_coords_relative.y);
416 if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) {
419 if (node_coords_relative.y < 0.0) {
420 theta_pos = motion_table.num_angle_quantization - node_coords_relative.theta;
422 theta_pos = node_coords_relative.theta;
424 const int x_pos = node_coords_relative.x + floored_size;
425 const int y_pos =
static_cast<int>(mirrored_relative_y);
427 x_pos * ceiling_size * motion_table.num_angle_quantization +
428 y_pos * motion_table.num_angle_quantization +
430 motion_heuristic = dist_heuristic_lookup_table[index];
431 }
else if (obstacle_heuristic == 0.0) {
432 static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
433 to[0] = goal_coords.x;
434 to[1] = goal_coords.y;
436 from[0] = node_coords.x;
437 from[1] = node_coords.y;
439 motion_heuristic = motion_table.state_space->distance(from(), to());
442 return motion_heuristic;
446 const float & lookup_table_dim,
447 const MotionModel & ,
448 const unsigned int & dim_3_size,
452 if (!search_info.allow_reverse_expansion) {
453 motion_table.state_space = std::make_shared<ompl::base::DubinsStateSpace>(
454 search_info.minimum_turning_radius);
455 motion_table.motion_model = MotionModel::DUBIN;
457 motion_table.state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
458 search_info.minimum_turning_radius);
459 motion_table.motion_model = MotionModel::REEDS_SHEPP;
461 motion_table.lattice_metadata =
464 ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
468 size_lookup = lookup_table_dim;
469 float motion_heuristic = 0.0;
470 unsigned int index = 0;
471 int dim_3_size_int =
static_cast<int>(dim_3_size);
478 dist_heuristic_lookup_table.resize(size_lookup * ceil(size_lookup / 2.0) * dim_3_size_int);
479 for (
float x = ceil(-size_lookup / 2.0); x <= floor(size_lookup / 2.0); x += 1.0) {
480 for (
float y = 0.0; y <= floor(size_lookup / 2.0); y += 1.0) {
481 for (
int heading = 0; heading != dim_3_size_int; heading++) {
485 motion_heuristic = motion_table.state_space->distance(from(), to());
486 dist_heuristic_lookup_table[index] = motion_heuristic;
494 std::function<
bool(
const uint64_t &,
497 const bool & traverse_unknown,
498 NodeVector & neighbors)
503 Coordinates initial_node_coords, motion_projection;
504 unsigned int direction_change_index = 0;
507 direction_change_index);
508 const float & grid_resolution = motion_table.lattice_metadata.grid_resolution;
510 for (
unsigned int i = 0; i != motion_primitives.size(); i++) {
511 const MotionPose & end_pose = motion_primitives[i]->poses.back();
512 motion_projection.x = this->pose.x + (end_pose._x / grid_resolution);
513 motion_projection.y = this->pose.y + (end_pose._y / grid_resolution);
514 motion_projection.theta = motion_primitives[i]->end_angle ;
521 if (i >= direction_change_index) {
523 float opposite_heading_theta =
524 motion_projection.theta - (motion_table.num_angle_quantization / 2);
525 if (opposite_heading_theta < 0) {
526 opposite_heading_theta += motion_table.num_angle_quantization;
528 if (opposite_heading_theta > motion_table.num_angle_quantization) {
529 opposite_heading_theta -= motion_table.num_angle_quantization;
531 motion_projection.theta = opposite_heading_theta;
535 static_cast<unsigned int>(motion_projection.x),
536 static_cast<unsigned int>(motion_projection.y),
537 static_cast<unsigned int>(motion_projection.theta));
539 if (NeighborGetter(index, neighbor) && !neighbor->
wasVisited()) {
542 initial_node_coords = neighbor->pose;
548 motion_projection.theta));
553 traverse_unknown, collision_checker, motion_primitives[i],
backwards))
558 neighbors.push_back(neighbor);
560 neighbor->
setPose(initial_node_coords);
574 while (current_node->parent) {
576 current_node = current_node->parent;
587 NodeLattice::CoordinateVector & path)
591 const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution;
596 initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution);
597 initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution);
598 initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle);
600 for (
auto it = prim->poses.crbegin(); it != prim->poses.crend(); ++it) {
602 prim_pose.x = initial_pose.x + (it->_x / grid_resolution);
603 prim_pose.y = initial_pose.y + (it->_y / grid_resolution);
607 prim_pose.theta = std::fmod(it->_theta + M_PI, 2.0 * M_PI);
609 prim_pose.theta = it->_theta;
611 path.push_back(prim_pose);
615 path.push_back(current_node->pose);
616 path.back().theta = NodeLattice::motion_table.getAngleFromBin(path.back().theta);
A costmap grid collision checker.
bool inCollision(const float &x, const float &y, const float &theta, const bool &traverse_unknown)
Check if in collision with costmap and footprint at pose.
std::vector< float > & getPrecomputedAngles()
Get the angles of the precomputed footprint orientations.
float getCost()
Get cost at footprint pose in costmap.
NodeLattice implementation for graph, Hybrid-A*.
void getNeighbors(std::function< bool(const uint64_t &, nav2_smac_planner::NodeLattice *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
void backwards(bool back=true)
Sets that this primitive is moving in reverse.
uint64_t getIndex()
Gets cell index.
~NodeLattice()
A destructor for nav2_smac_planner::NodeLattice.
float getCost()
Gets the costmap cost at this node.
void reset()
Reset method for new search.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
float getTraversalCost(const NodePtr &child)
Get traversal cost of parent node to child node.
bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker, MotionPrimitive *primitive=nullptr, bool is_backwards=false)
Check if this node is valid.
static float getHeuristicCost(const Coordinates &node_coords, const CoordinateVector &goals_coords)
Get cost of heuristic of node.
void addNodeToPath(NodePtr current_node, CoordinateVector &path)
add node to the path
bool isBackward()
Gets if this primitive is moving in reverse.
bool wasVisited()
Gets if cell has been visited in search.
static void initMotionModel(const MotionModel &motion_model, unsigned int &size_x, unsigned int &size_y, unsigned int &angle_quantization, SearchInfo &search_info)
Initialize motion models.
MotionPrimitive *& getMotionPrimitive()
Gets the motion primitive used to achieve node in search.
static void precomputeDistanceHeuristic(const float &lookup_table_dim, const MotionModel &motion_model, const unsigned int &dim_3_size, const SearchInfo &search_info)
Compute the SE2 distance heuristic.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
void setMotionPrimitive(MotionPrimitive *prim)
Sets the motion primitive used to achieve node in search.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
static LatticeMetadata getLatticeMetadata(const std::string &lattice_filepath)
Get file metadata needed.
void initMotionModel(unsigned int &size_x_in, SearchInfo &search_info)
Initializing state lattice planner's motion model.
MotionPrimitivePtrs getMotionPrimitives(const NodeLattice *node, unsigned int &direction_change_index)
Get projections of motion models.
float & getAngleFromBin(const unsigned int &bin_idx)
Get the raw orientation from an angular bin.
A struct for poses in motion primitives.
A struct of all motion primitive data.
NodeHybrid implementation of coordinate structure.
Search properties and penalties.