#include <sbpl_arm_planner_params.h>
Public Member Functions | |
void | addMotionPrim (std::vector< double > mprim, bool add_converse, bool short_dist_mprim) |
add a motion primitive vector to the list | |
double | getLargestMotionPrimOffset () |
NOTE: For computing cost for IK and OS solutions. | |
double | getSmallestShoulderPanMotion () |
bool | initFromParamFile (FILE *fCfg) |
grab parameters from a text file | |
bool | initFromParamFile (std::string param_file) |
grab parameters from a text file | |
void | initFromParamServer () |
grab parameters from the ROS param server | |
bool | initFromResource (std::string url) |
use a resource retriever to grab params from a file | |
bool | initMotionPrimsFromFile (FILE *fCfg) |
grab motion primitives from a text file | |
void | precomputeSmoothingCosts () |
precompute the smoothing cost from each mprim to every other mprim | |
void | printMotionPrims (FILE *fOut) |
print the motion primitives | |
void | printParams (FILE *fOut) |
print out the parameters | |
void | printSmoothingCosts (FILE *fOut) |
print the smoothing cost table | |
SBPLArmPlannerParams () | |
default constructor (just assigns default values) | |
void | setCellCost (int cost_per_cell) |
set the cost per cell | |
~SBPLArmPlannerParams () | |
destructor | |
Public Attributes | |
int | angle_delta_ |
discretization of joint angles (default: 360) | |
int | cost_multiplier_ |
cost multiplier (so we don't have to deal with doubles) | |
int | cost_per_cell_ |
cost of moving one cell in the grid | |
int | cost_per_meter_ |
cost of moving one meter (only used when euclidean distance is used as the heuristic instead of dijkstra) | |
double | epsilon_ |
epsilon to be used by planner (epsilon is the bounds on the suboptimality of the solution of a weighted A* type search) | |
int | is_goal_function_ |
set which function to use to check if at goal position | |
double | max_mprim_offset_ |
std::vector< std::vector < double > > | mprims_ |
the 2D array of motion primitives | |
int | num_long_dist_mprims_ |
number of long distance motion primitives | |
int | num_mprims_ |
total number of motion primitives | |
int | num_short_dist_mprims_ |
number of short distance motion primitives | |
double | originX_ |
origin of collision space | |
double | originY_ |
double | originZ_ |
std::string | planner_name_ |
int | range1_cost_ |
int | range2_cost_ |
int | range3_cost_ |
double | resolution_ |
resolution of collision space | |
int | short_dist_mprims_thresh_c_ |
distance from goal pose in cells to switch to using short distance motion primitives + long distance motion primitives | |
double | short_dist_mprims_thresh_m_ |
distance from goal pose in meters to switch to using short distance motion primitives + long distance motion primitives | |
double | sizeX_ |
size of collision space | |
double | sizeY_ |
double | sizeZ_ |
std::vector< std::vector< int > > | smoothing_cost_ |
cost of transitioning from mprim to mprim, this provides the smoothing factor | |
int | solve_for_ik_thresh_ |
double | solve_for_ik_thresh_m_ |
bool | sum_heuristics_ |
add the h_rpy & h_xyz together | |
bool | two_calls_to_op_ |
bool | use_6d_pose_goal_ |
plan to a 6D pose goal (if false, plans to 3D goal {x,y,z}) | |
bool | use_dijkstra_heuristic_ |
use a 3D dijkstra search as the heuristic | |
bool | use_ik_ |
use IK to try to satisfy the orientation constraint | |
bool | use_multires_mprims_ |
enable multi-resolution motion primitives | |
bool | use_orientation_solver_ |
use the orientation solver to try to satisfy orientation constraint | |
bool | use_research_heuristic_ |
bool | use_smoothing_ |
enable path smoothing during search | |
bool | use_uniform_cost_ |
uniform cost when moving from one cell to another (if false, a cost will be applied based on distance from nearest obstacle) | |
bool | verbose_ |
spew out all debugging text | |
bool | verbose_collisions_ |
spew out all collision checking related debugging text | |
bool | verbose_heuristics_ |
spew out all heuristic related debugging text |
Definition at line 46 of file sbpl_arm_planner_params.h.
SBPLArmPlannerParams::SBPLArmPlannerParams | ( | ) |
default constructor (just assigns default values)
Definition at line 33 of file sbpl_arm_planner_params.cpp.
SBPLArmPlannerParams::~SBPLArmPlannerParams | ( | ) | [inline] |
destructor
Definition at line 55 of file sbpl_arm_planner_params.h.
void SBPLArmPlannerParams::addMotionPrim | ( | std::vector< double > | mprim, | |
bool | add_converse, | |||
bool | short_dist_mprim | |||
) |
add a motion primitive vector to the list
Definition at line 412 of file sbpl_arm_planner_params.cpp.
double SBPLArmPlannerParams::getLargestMotionPrimOffset | ( | ) |
NOTE: For computing cost for IK and OS solutions.
Definition at line 560 of file sbpl_arm_planner_params.cpp.
double SBPLArmPlannerParams::getSmallestShoulderPanMotion | ( | ) |
Definition at line 545 of file sbpl_arm_planner_params.cpp.
bool SBPLArmPlannerParams::initFromParamFile | ( | FILE * | fCfg | ) |
grab parameters from a text file
Definition at line 199 of file sbpl_arm_planner_params.cpp.
bool SBPLArmPlannerParams::initFromParamFile | ( | std::string | param_file | ) |
grab parameters from a text file
Definition at line 102 of file sbpl_arm_planner_params.cpp.
void SBPLArmPlannerParams::initFromParamServer | ( | ) |
grab parameters from the ROS param server
Definition at line 72 of file sbpl_arm_planner_params.cpp.
bool SBPLArmPlannerParams::initFromResource | ( | std::string | url | ) |
use a resource retriever to grab params from a file
bool SBPLArmPlannerParams::initMotionPrimsFromFile | ( | FILE * | fCfg | ) |
grab motion primitives from a text file
Definition at line 125 of file sbpl_arm_planner_params.cpp.
void SBPLArmPlannerParams::precomputeSmoothingCosts | ( | ) |
precompute the smoothing cost from each mprim to every other mprim
Definition at line 499 of file sbpl_arm_planner_params.cpp.
void SBPLArmPlannerParams::printMotionPrims | ( | FILE * | fOut | ) |
print the motion primitives
Definition at line 459 of file sbpl_arm_planner_params.cpp.
void SBPLArmPlannerParams::printParams | ( | FILE * | fOut | ) |
print out the parameters
Definition at line 481 of file sbpl_arm_planner_params.cpp.
void SBPLArmPlannerParams::printSmoothingCosts | ( | FILE * | fOut | ) |
print the smoothing cost table
Definition at line 520 of file sbpl_arm_planner_params.cpp.
void SBPLArmPlannerParams::setCellCost | ( | int | cost_per_cell | ) |
set the cost per cell
Definition at line 405 of file sbpl_arm_planner_params.cpp.
discretization of joint angles (default: 360)
Definition at line 135 of file sbpl_arm_planner_params.h.
cost multiplier (so we don't have to deal with doubles)
Definition at line 164 of file sbpl_arm_planner_params.h.
cost of moving one cell in the grid
Definition at line 171 of file sbpl_arm_planner_params.h.
cost of moving one meter (only used when euclidean distance is used as the heuristic instead of dijkstra)
Definition at line 175 of file sbpl_arm_planner_params.h.
epsilon to be used by planner (epsilon is the bounds on the suboptimality of the solution of a weighted A* type search)
Definition at line 98 of file sbpl_arm_planner_params.h.
set which function to use to check if at goal position
Definition at line 178 of file sbpl_arm_planner_params.h.
Definition at line 184 of file sbpl_arm_planner_params.h.
std::vector<std::vector<double> > SBPLArmPlannerParams::mprims_ |
the 2D array of motion primitives
Definition at line 138 of file sbpl_arm_planner_params.h.
number of long distance motion primitives
Definition at line 144 of file sbpl_arm_planner_params.h.
total number of motion primitives
Definition at line 141 of file sbpl_arm_planner_params.h.
number of short distance motion primitives
Definition at line 147 of file sbpl_arm_planner_params.h.
origin of collision space
Definition at line 195 of file sbpl_arm_planner_params.h.
Definition at line 196 of file sbpl_arm_planner_params.h.
Definition at line 197 of file sbpl_arm_planner_params.h.
std::string SBPLArmPlannerParams::planner_name_ |
Definition at line 157 of file sbpl_arm_planner_params.h.
Definition at line 166 of file sbpl_arm_planner_params.h.
Definition at line 167 of file sbpl_arm_planner_params.h.
Definition at line 168 of file sbpl_arm_planner_params.h.
resolution of collision space
Definition at line 192 of file sbpl_arm_planner_params.h.
distance from goal pose in cells to switch to using short distance motion primitives + long distance motion primitives
Definition at line 151 of file sbpl_arm_planner_params.h.
distance from goal pose in meters to switch to using short distance motion primitives + long distance motion primitives
Definition at line 155 of file sbpl_arm_planner_params.h.
double SBPLArmPlannerParams::sizeX_ |
size of collision space
Definition at line 187 of file sbpl_arm_planner_params.h.
double SBPLArmPlannerParams::sizeY_ |
Definition at line 188 of file sbpl_arm_planner_params.h.
double SBPLArmPlannerParams::sizeZ_ |
Definition at line 189 of file sbpl_arm_planner_params.h.
std::vector<std::vector<int> > SBPLArmPlannerParams::smoothing_cost_ |
cost of transitioning from mprim to mprim, this provides the smoothing factor
Definition at line 161 of file sbpl_arm_planner_params.h.
Definition at line 199 of file sbpl_arm_planner_params.h.
Definition at line 200 of file sbpl_arm_planner_params.h.
add the h_rpy & h_xyz together
Definition at line 119 of file sbpl_arm_planner_params.h.
Definition at line 180 of file sbpl_arm_planner_params.h.
plan to a 6D pose goal (if false, plans to 3D goal {x,y,z})
Definition at line 116 of file sbpl_arm_planner_params.h.
use a 3D dijkstra search as the heuristic
Definition at line 104 of file sbpl_arm_planner_params.h.
use IK to try to satisfy the orientation constraint
Definition at line 110 of file sbpl_arm_planner_params.h.
enable multi-resolution motion primitives
Definition at line 101 of file sbpl_arm_planner_params.h.
use the orientation solver to try to satisfy orientation constraint
Definition at line 107 of file sbpl_arm_planner_params.h.
Definition at line 182 of file sbpl_arm_planner_params.h.
enable path smoothing during search
Definition at line 113 of file sbpl_arm_planner_params.h.
uniform cost when moving from one cell to another (if false, a cost will be applied based on distance from nearest obstacle)
Definition at line 123 of file sbpl_arm_planner_params.h.
spew out all debugging text
Definition at line 126 of file sbpl_arm_planner_params.h.
spew out all collision checking related debugging text
Definition at line 132 of file sbpl_arm_planner_params.h.
spew out all heuristic related debugging text
Definition at line 129 of file sbpl_arm_planner_params.h.