#include <sbpl_params.h>
Public Member Functions | |
SBPLParams () | |
default constructor (just assigns default values) | |
~SBPLArmPlannerParams () | |
destructor | |
Public Attributes | |
int | angle_delta_ |
discretization of joint angles (default: 360) | |
std::string | arm_log_ |
std::string | arm_log_level_ |
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) | |
int | cost_per_second_ |
std::string | cspace_log_ |
std::string | cspace_log_level_ |
std::string | environment_type_ |
double | epsilon_ |
epsilon to be used by planner (epsilon is the bounds on the suboptimality of the solution of a weighted A* type search) | |
std::string | expands2_log_ |
std::string | expands2_log_level_ |
std::string | expands_log_ |
std::string | expands_log_level_ |
double | fa_resolution_ |
std::string | group_name_ |
std::string | ik_log_ |
std::string | ik_log_level_ |
int | is_goal_function_ |
set which function to use to check if at goal position | |
std::vector< double > | joint_vel_ |
double | max_mprim_offset_ |
std::vector< std::string > | motion_primitive_type_names_ |
std::vector< MotionPrimitive > | mp_ |
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_ |
std::vector< std::string > | planning_joints_ |
int | range1_cost_ |
int | range2_cost_ |
int | range3_cost_ |
std::string | reference_frame_ |
double | resolution_ |
resolution of collision space | |
double | rpy_resolution_ |
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::string | solution_log_ |
std::string | solution_log_level_ |
int | solve_for_ik_thresh_ |
double | solve_for_ik_thresh_m_ |
bool | sum_heuristics_ |
add the h_rpy & h_xyz together | |
double | time_per_cell_ |
bool | two_calls_to_op_ |
call the orientation solver twice (try rotating the wrist clockwise and then counter-clockwise) | |
bool | use_6d_pose_goal_ |
plan to a 6D pose goal (if false, plans to 3D goal {x,y,z}) | |
bool | use_bfs_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_ |
use the elbow heuristic | |
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 | |
double | xyz_resolution_ |
Definition at line 59 of file sbpl_params.h.
default constructor (just assigns default values)
sbpl_interface::SBPLParams::~SBPLArmPlannerParams | ( | ) | [inline] |
destructor
Definition at line 67 of file sbpl_params.h.
discretization of joint angles (default: 360)
Definition at line 105 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::arm_log_ |
Definition at line 191 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::arm_log_level_ |
Definition at line 197 of file sbpl_params.h.
cost multiplier (so we don't have to deal with doubles)
Definition at line 132 of file sbpl_params.h.
cost of moving one cell in the grid
Definition at line 139 of file sbpl_params.h.
cost of moving one meter (only used when euclidean distance is used as the heuristic instead of dijkstra)
Definition at line 143 of file sbpl_params.h.
Definition at line 180 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::cspace_log_ |
Definition at line 192 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::cspace_log_level_ |
Definition at line 198 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::environment_type_ |
Definition at line 129 of file sbpl_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 67 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::expands2_log_ |
Definition at line 189 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::expands2_log_level_ |
Definition at line 195 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::expands_log_ |
Definition at line 188 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::expands_log_level_ |
Definition at line 194 of file sbpl_params.h.
Definition at line 178 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::group_name_ |
Definition at line 184 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::ik_log_ |
Definition at line 190 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::ik_log_level_ |
Definition at line 196 of file sbpl_params.h.
set which function to use to check if at goal position
Definition at line 146 of file sbpl_params.h.
std::vector<double> sbpl_interface::SBPLParams::joint_vel_ |
Definition at line 182 of file sbpl_params.h.
Definition at line 154 of file sbpl_params.h.
std::vector<std::string> sbpl_interface::SBPLParams::motion_primitive_type_names_ |
Definition at line 201 of file sbpl_params.h.
std::vector<MotionPrimitive> sbpl_interface::SBPLParams::mp_ |
Definition at line 175 of file sbpl_params.h.
std::vector<std::vector<double> > sbpl_interface::SBPLParams::mprims_ |
the 2D array of motion primitives
Definition at line 108 of file sbpl_params.h.
number of long distance motion primitives
Definition at line 114 of file sbpl_params.h.
total number of motion primitives
Definition at line 111 of file sbpl_params.h.
number of short distance motion primitives
Definition at line 117 of file sbpl_params.h.
origin of collision space
Definition at line 165 of file sbpl_params.h.
Definition at line 166 of file sbpl_params.h.
Definition at line 167 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::planner_name_ |
Definition at line 127 of file sbpl_params.h.
std::vector<std::string> sbpl_interface::SBPLParams::planning_joints_ |
Definition at line 185 of file sbpl_params.h.
Definition at line 134 of file sbpl_params.h.
Definition at line 135 of file sbpl_params.h.
Definition at line 136 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::reference_frame_ |
Definition at line 172 of file sbpl_params.h.
resolution of collision space
Definition at line 162 of file sbpl_params.h.
Definition at line 177 of file sbpl_params.h.
distance from goal pose in cells to switch to using short distance motion primitives + long distance motion primitives
Definition at line 121 of file sbpl_params.h.
distance from goal pose in meters to switch to using short distance motion primitives + long distance motion primitives
Definition at line 125 of file sbpl_params.h.
size of collision space
Definition at line 157 of file sbpl_params.h.
Definition at line 158 of file sbpl_params.h.
Definition at line 159 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::solution_log_ |
Definition at line 193 of file sbpl_params.h.
std::string sbpl_interface::SBPLParams::solution_log_level_ |
Definition at line 199 of file sbpl_params.h.
Definition at line 169 of file sbpl_params.h.
Definition at line 170 of file sbpl_params.h.
add the h_rpy & h_xyz together
Definition at line 89 of file sbpl_params.h.
Definition at line 181 of file sbpl_params.h.
call the orientation solver twice (try rotating the wrist clockwise and then counter-clockwise)
Definition at line 149 of file sbpl_params.h.
plan to a 6D pose goal (if false, plans to 3D goal {x,y,z})
Definition at line 86 of file sbpl_params.h.
use a 3D dijkstra search as the heuristic
Definition at line 77 of file sbpl_params.h.
use IK to try to satisfy the orientation constraint
Definition at line 83 of file sbpl_params.h.
enable multi-resolution motion primitives
Definition at line 74 of file sbpl_params.h.
use the orientation solver to try to satisfy orientation constraint
Definition at line 80 of file sbpl_params.h.
use the elbow heuristic
Definition at line 152 of file sbpl_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 93 of file sbpl_params.h.
spew out all debugging text
Definition at line 96 of file sbpl_params.h.
spew out all collision checking related debugging text
Definition at line 102 of file sbpl_params.h.
spew out all heuristic related debugging text
Definition at line 99 of file sbpl_params.h.
Definition at line 176 of file sbpl_params.h.