Struct HybridMotionTable

Struct Documentation

struct HybridMotionTable

A table of motion primitives and related functions.

Public Functions

inline HybridMotionTable()

A constructor for nav2_smac_planner::HybridMotionTable.

void initDubin(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)

Initializing using Dubin model.

Parameters:
  • size_x_in – Size of costmap in X

  • size_y_in – Size of costmap in Y

  • angle_quantization_in – Size of costmap in bin sizes

  • search_info – Parameters for searching

void initReedsShepp(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)

Initializing using Reeds-Shepp model.

Parameters:
  • size_x_in – Size of costmap in X

  • size_y_in – Size of costmap in Y

  • angle_quantization_in – Size of costmap in bin sizes

  • search_info – Parameters for searching

MotionPoses getProjections(const NodeHybrid *node)

Get projections of motion models.

Parameters:

node – Ptr to NodeHybrid

Returns:

A set of motion poses

unsigned int getClosestAngularBin(const double &theta)

Get the angular bin to use from a raw orientation.

Parameters:

theta – Angle in radians

Returns:

bin index of closest angle to request

float getAngleFromBin(const unsigned int &bin_idx)

Get the raw orientation from an angular bin.

Parameters:

bin_idx – Index of the bin

Returns:

Raw orientation in radians

Public Members

MotionModel motion_model = MotionModel::UNKNOWN
MotionPoses projections
unsigned int size_x
unsigned int num_angle_quantization
float num_angle_quantization_float
float min_turning_radius
float bin_size
float change_penalty
float non_straight_penalty
float cost_penalty
float reverse_penalty
float travel_distance_reward
ompl::base::StateSpacePtr state_space
std::vector<std::vector<double>> delta_xs
std::vector<std::vector<double>> delta_ys
std::vector<TrigValues> trig_values