26 #include "ompl/base/ScopedState.h"
27 #include "ompl/base/spaces/DubinsStateSpace.h"
28 #include "ompl/base/spaces/ReedsSheppStateSpace.h"
30 #include "nav2_smac_planner/node_lattice.hpp"
32 using namespace std::chrono;
34 namespace nav2_smac_planner
38 LatticeMotionTable NodeLattice::motion_table;
39 float NodeLattice::size_lookup = 25;
40 LookupTable NodeLattice::dist_heuristic_lookup_table;
48 void LatticeMotionTable::initMotionModel(
49 unsigned int & size_x_in,
53 change_penalty = search_info.change_penalty;
54 non_straight_penalty = search_info.non_straight_penalty;
55 cost_penalty = search_info.cost_penalty;
56 reverse_penalty = search_info.reverse_penalty;
57 travel_distance_reward = 1.0f - search_info.retrospective_penalty;
58 allow_reverse_expansion = search_info.allow_reverse_expansion;
59 rotation_penalty = search_info.rotation_penalty;
60 min_turning_radius = search_info.minimum_turning_radius;
62 if (current_lattice_filepath == search_info.lattice_filepath) {
65 current_lattice_filepath = search_info.lattice_filepath;
68 lattice_metadata = getLatticeMetadata(current_lattice_filepath);
69 std::ifstream latticeFile(current_lattice_filepath);
70 if (!latticeFile.is_open()) {
71 throw std::runtime_error(
"Could not open lattice file");
75 num_angle_quantization = lattice_metadata.number_of_headings;
78 if (!allow_reverse_expansion) {
79 state_space = std::make_shared<ompl::base::DubinsStateSpace>(
80 lattice_metadata.min_turning_radius);
81 motion_model = MotionModel::DUBIN;
83 state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
84 lattice_metadata.min_turning_radius);
85 motion_model = MotionModel::REEDS_SHEPP;
90 float prev_start_angle = 0.0;
91 std::vector<MotionPrimitive> primitives;
92 nlohmann::json json_primitives = json[
"primitives"];
93 for (
unsigned int i = 0; i < json_primitives.size(); ++i) {
95 fromJsonToMotionPrimitive(json_primitives[i], new_primitive);
97 if (prev_start_angle != new_primitive.start_angle) {
98 motion_primitives.push_back(primitives);
100 prev_start_angle = new_primitive.start_angle;
102 primitives.push_back(new_primitive);
104 motion_primitives.push_back(primitives);
107 trig_values.reserve(lattice_metadata.number_of_headings);
108 for (
unsigned int i = 0; i < lattice_metadata.heading_angles.size(); ++i) {
109 trig_values.emplace_back(
110 cos(lattice_metadata.heading_angles[i]),
111 sin(lattice_metadata.heading_angles[i]));
115 MotionPrimitivePtrs LatticeMotionTable::getMotionPrimitives(
117 unsigned int & direction_change_index)
119 MotionPrimitives & prims_at_heading = motion_primitives[node->pose.theta];
120 MotionPrimitivePtrs primitive_projection_list;
121 for (
unsigned int i = 0; i != prims_at_heading.size(); i++) {
122 primitive_projection_list.push_back(&prims_at_heading[i]);
126 direction_change_index =
static_cast<unsigned int>(primitive_projection_list.size());
128 if (allow_reverse_expansion) {
130 double reserve_heading = node->pose.theta - (num_angle_quantization / 2);
131 if (reserve_heading < 0) {
132 reserve_heading += num_angle_quantization;
134 if (reserve_heading > num_angle_quantization) {
135 reserve_heading -= num_angle_quantization;
138 MotionPrimitives & prims_at_reverse_heading = motion_primitives[reserve_heading];
139 for (
unsigned int i = 0; i != prims_at_reverse_heading.size(); i++) {
140 primitive_projection_list.push_back(&prims_at_reverse_heading[i]);
144 return primitive_projection_list;
147 LatticeMetadata LatticeMotionTable::getLatticeMetadata(
const std::string & lattice_filepath)
149 std::ifstream lattice_file(lattice_filepath);
150 if (!lattice_file.is_open()) {
151 throw std::runtime_error(
"Could not open lattice file!");
157 fromJsonToMetaData(j[
"lattice_metadata"], metadata);
161 unsigned int LatticeMotionTable::getClosestAngularBin(
const double & theta)
163 float min_dist = std::numeric_limits<float>::max();
164 unsigned int closest_idx = 0;
166 for (
unsigned int i = 0; i != lattice_metadata.heading_angles.size(); i++) {
167 dist = fabs(angles::shortest_angular_distance(theta, lattice_metadata.heading_angles[i]));
168 if (dist < min_dist) {
176 float & LatticeMotionTable::getAngleFromBin(
const unsigned int & bin_idx)
178 return lattice_metadata.heading_angles[bin_idx];
181 double LatticeMotionTable::getAngle(
const double & theta)
183 return getClosestAngularBin(theta);
186 NodeLattice::NodeLattice(
const uint64_t index)
188 pose(0.0f, 0.0f, 0.0f),
189 _cell_cost(std::numeric_limits<float>::quiet_NaN()),
190 _accumulated_cost(std::numeric_limits<float>::max()),
193 _motion_primitive(nullptr),
195 _is_node_valid(false)
207 _cell_cost = std::numeric_limits<float>::quiet_NaN();
208 _accumulated_cost = std::numeric_limits<float>::max();
209 _was_visited =
false;
213 _motion_primitive =
nullptr;
215 _is_node_valid =
false;
219 const bool & traverse_unknown,
225 if (!std::isnan(_cell_cost)) {
226 return _is_node_valid;
232 const double angle = std::fmod(motion_table.
getAngleFromBin(this->pose.theta),
233 2.0 * M_PI) / bin_size;
235 this->pose.x, this->pose.y, angle , traverse_unknown))
237 _is_node_valid =
false;
238 _cell_cost = collision_checker->
getCost();
243 float max_cell_cost = collision_checker->
getCost();
246 if (motion_primitive) {
247 const float & grid_resolution = motion_table.lattice_metadata.grid_resolution;
248 const float & resolution_diag_sq = 2.0 * grid_resolution * grid_resolution;
249 MotionPose last_pose(1e9, 1e9, 1e9, TurnDirection::UNKNOWN);
250 MotionPose pose_dist(0.0, 0.0, 0.0, TurnDirection::UNKNOWN);
254 initial_pose._x = this->pose.x - (motion_primitive->poses.back()._x / grid_resolution);
255 initial_pose._y = this->pose.y - (motion_primitive->poses.back()._y / grid_resolution);
256 initial_pose._theta = motion_table.
getAngleFromBin(motion_primitive->start_angle);
258 for (
auto it = motion_primitive->poses.begin(); it != motion_primitive->poses.end(); ++it) {
260 pose_dist = *it - last_pose;
262 if (pose_dist._x * pose_dist._x + pose_dist._y * pose_dist._y > resolution_diag_sq) {
265 prim_pose._x = initial_pose._x + (it->_x / grid_resolution);
266 prim_pose._y = initial_pose._y + (it->_y / grid_resolution);
270 prim_pose._theta = std::fmod(it->_theta + M_PI, 2.0 * M_PI);
272 prim_pose._theta = std::fmod(it->_theta, 2.0 * M_PI);
277 prim_pose._theta / bin_size ,
280 _is_node_valid =
false;
281 _cell_cost = std::max(max_cell_cost, collision_checker->
getCost());
284 max_cell_cost = std::max(max_cell_cost, collision_checker->
getCost());
289 _cell_cost = max_cell_cost;
290 _is_node_valid =
true;
291 return _is_node_valid;
296 const float normalized_cost = child->
getCost() / 252.0;
297 if (std::isnan(normalized_cost)) {
298 throw std::runtime_error(
299 "Node attempted to get traversal "
300 "cost without a known collision cost!");
306 const float prim_length =
307 transition_prim->trajectory_length / motion_table.lattice_metadata.grid_resolution;
308 if (prim ==
nullptr) {
313 if (transition_prim->trajectory_length < 1e-4) {
314 return motion_table.rotation_penalty * (1.0 + motion_table.cost_penalty * normalized_cost);
317 float travel_cost = 0.0;
318 float travel_cost_raw = prim_length *
319 (motion_table.travel_distance_reward + motion_table.cost_penalty * normalized_cost);
321 if (transition_prim->arc_length < 0.001) {
323 travel_cost = travel_cost_raw;
325 if (prim->left_turn == transition_prim->left_turn) {
327 travel_cost = travel_cost_raw * motion_table.non_straight_penalty;
330 travel_cost = travel_cost_raw *
331 (motion_table.non_straight_penalty + motion_table.change_penalty);
338 travel_cost *= motion_table.reverse_penalty;
350 node_coords, goal_coords, motion_table.cost_penalty);
351 const float distance_heuristic =
353 return std::max(obstacle_heuristic, distance_heuristic);
357 const MotionModel & motion_model,
358 unsigned int & size_x,
363 if (motion_model != MotionModel::STATE_LATTICE) {
364 throw std::runtime_error(
365 "Invalid motion model for Lattice node. Please select"
366 " STATE_LATTICE and provide a valid lattice file.");
375 const float & obstacle_heuristic)
384 const TrigValues & trig_vals = motion_table.trig_values[goal_coords.theta];
385 const float cos_th = trig_vals.first;
386 const float sin_th = -trig_vals.second;
387 const float dx = node_coords.x - goal_coords.x;
388 const float dy = node_coords.y - goal_coords.y;
390 double dtheta_bin = node_coords.theta - goal_coords.theta;
391 if (dtheta_bin < 0) {
392 dtheta_bin += motion_table.num_angle_quantization;
394 if (dtheta_bin > motion_table.num_angle_quantization) {
395 dtheta_bin -= motion_table.num_angle_quantization;
399 round(dx * cos_th - dy * sin_th),
400 round(dx * sin_th + dy * cos_th),
406 float motion_heuristic = 0.0;
407 const int floored_size = floor(size_lookup / 2.0);
408 const int ceiling_size = ceil(size_lookup / 2.0);
409 const float mirrored_relative_y = abs(node_coords_relative.y);
410 if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) {
413 if (node_coords_relative.y < 0.0) {
414 theta_pos = motion_table.num_angle_quantization - node_coords_relative.theta;
416 theta_pos = node_coords_relative.theta;
418 const int x_pos = node_coords_relative.x + floored_size;
419 const int y_pos =
static_cast<int>(mirrored_relative_y);
421 x_pos * ceiling_size * motion_table.num_angle_quantization +
422 y_pos * motion_table.num_angle_quantization +
424 motion_heuristic = dist_heuristic_lookup_table[index];
425 }
else if (obstacle_heuristic == 0.0) {
426 static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
427 to[0] = goal_coords.x;
428 to[1] = goal_coords.y;
430 from[0] = node_coords.x;
431 from[1] = node_coords.y;
433 motion_heuristic = motion_table.state_space->distance(from(), to());
436 return motion_heuristic;
440 const float & lookup_table_dim,
441 const MotionModel & ,
442 const unsigned int & dim_3_size,
446 if (!search_info.allow_reverse_expansion) {
447 motion_table.state_space = std::make_shared<ompl::base::DubinsStateSpace>(
448 search_info.minimum_turning_radius);
449 motion_table.motion_model = MotionModel::DUBIN;
451 motion_table.state_space = std::make_shared<ompl::base::ReedsSheppStateSpace>(
452 search_info.minimum_turning_radius);
453 motion_table.motion_model = MotionModel::REEDS_SHEPP;
455 motion_table.lattice_metadata =
458 ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space);
462 size_lookup = lookup_table_dim;
463 float motion_heuristic = 0.0;
464 unsigned int index = 0;
465 int dim_3_size_int =
static_cast<int>(dim_3_size);
472 dist_heuristic_lookup_table.resize(size_lookup * ceil(size_lookup / 2.0) * dim_3_size_int);
473 for (
float x = ceil(-size_lookup / 2.0); x <= floor(size_lookup / 2.0); x += 1.0) {
474 for (
float y = 0.0; y <= floor(size_lookup / 2.0); y += 1.0) {
475 for (
int heading = 0; heading != dim_3_size_int; heading++) {
479 motion_heuristic = motion_table.state_space->distance(from(), to());
480 dist_heuristic_lookup_table[index] = motion_heuristic;
488 std::function<
bool(
const uint64_t &,
491 const bool & traverse_unknown,
492 NodeVector & neighbors)
497 Coordinates initial_node_coords, motion_projection;
498 unsigned int direction_change_index = 0;
501 direction_change_index);
502 const float & grid_resolution = motion_table.lattice_metadata.grid_resolution;
504 for (
unsigned int i = 0; i != motion_primitives.size(); i++) {
505 const MotionPose & end_pose = motion_primitives[i]->poses.back();
506 motion_projection.x = this->pose.x + (end_pose._x / grid_resolution);
507 motion_projection.y = this->pose.y + (end_pose._y / grid_resolution);
508 motion_projection.theta = motion_primitives[i]->end_angle ;
515 if (i >= direction_change_index) {
517 float opposite_heading_theta =
518 motion_projection.theta - (motion_table.num_angle_quantization / 2);
519 if (opposite_heading_theta < 0) {
520 opposite_heading_theta += motion_table.num_angle_quantization;
522 if (opposite_heading_theta > motion_table.num_angle_quantization) {
523 opposite_heading_theta -= motion_table.num_angle_quantization;
525 motion_projection.theta = opposite_heading_theta;
529 static_cast<unsigned int>(motion_projection.x),
530 static_cast<unsigned int>(motion_projection.y),
531 static_cast<unsigned int>(motion_projection.theta));
533 if (NeighborGetter(index, neighbor) && !neighbor->
wasVisited()) {
536 initial_node_coords = neighbor->pose;
542 motion_projection.theta));
547 traverse_unknown, collision_checker, motion_primitives[i],
backwards))
552 neighbors.push_back(neighbor);
554 neighbor->
setPose(initial_node_coords);
568 while (current_node->parent) {
570 current_node = current_node->parent;
581 NodeLattice::CoordinateVector & path)
585 const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution;
590 initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution);
591 initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution);
592 initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle);
594 for (
auto it = prim->poses.crbegin(); it != prim->poses.crend(); ++it) {
596 prim_pose.x = initial_pose.x + (it->_x / grid_resolution);
597 prim_pose.y = initial_pose.y + (it->_y / grid_resolution);
601 prim_pose.theta = std::fmod(it->_theta + M_PI, 2.0 * M_PI);
603 prim_pose.theta = it->_theta;
605 path.push_back(prim_pose);
609 path.push_back(current_node->pose);
610 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.
static float getHeuristicCost(const Coordinates &node_coords, const Coordinates &goal_coordinates)
Get cost of heuristic of 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.
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.