Public Member Functions | Public Attributes
sbpl_interface::SBPLParams Class Reference

#include <sbpl_params.h>

List of all members.

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< MotionPrimitivemp_
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_

Detailed Description

Definition at line 65 of file sbpl_params.h.


Constructor & Destructor Documentation

default constructor (just assigns default values)

destructor

Definition at line 73 of file sbpl_params.h.


Member Data Documentation

discretization of joint angles (default: 360)

Definition at line 111 of file sbpl_params.h.

Definition at line 197 of file sbpl_params.h.

Definition at line 203 of file sbpl_params.h.

cost multiplier (so we don't have to deal with doubles)

Definition at line 138 of file sbpl_params.h.

cost of moving one cell in the grid

Definition at line 145 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 149 of file sbpl_params.h.

Definition at line 186 of file sbpl_params.h.

Definition at line 198 of file sbpl_params.h.

Definition at line 204 of file sbpl_params.h.

Definition at line 135 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 73 of file sbpl_params.h.

Definition at line 195 of file sbpl_params.h.

Definition at line 201 of file sbpl_params.h.

Definition at line 194 of file sbpl_params.h.

Definition at line 200 of file sbpl_params.h.

Definition at line 184 of file sbpl_params.h.

Definition at line 190 of file sbpl_params.h.

Definition at line 196 of file sbpl_params.h.

Definition at line 202 of file sbpl_params.h.

set which function to use to check if at goal position

Definition at line 152 of file sbpl_params.h.

Definition at line 188 of file sbpl_params.h.

Definition at line 160 of file sbpl_params.h.

Definition at line 207 of file sbpl_params.h.

Definition at line 181 of file sbpl_params.h.

std::vector<std::vector<double> > sbpl_interface::SBPLParams::mprims_

the 2D array of motion primitives

Definition at line 114 of file sbpl_params.h.

number of long distance motion primitives

Definition at line 120 of file sbpl_params.h.

total number of motion primitives

Definition at line 117 of file sbpl_params.h.

number of short distance motion primitives

Definition at line 123 of file sbpl_params.h.

origin of collision space

Definition at line 171 of file sbpl_params.h.

Definition at line 172 of file sbpl_params.h.

Definition at line 173 of file sbpl_params.h.

Definition at line 133 of file sbpl_params.h.

Definition at line 191 of file sbpl_params.h.

Definition at line 140 of file sbpl_params.h.

Definition at line 141 of file sbpl_params.h.

Definition at line 142 of file sbpl_params.h.

Definition at line 178 of file sbpl_params.h.

resolution of collision space

Definition at line 168 of file sbpl_params.h.

Definition at line 183 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 127 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 131 of file sbpl_params.h.

size of collision space

Definition at line 163 of file sbpl_params.h.

Definition at line 164 of file sbpl_params.h.

Definition at line 165 of file sbpl_params.h.

Definition at line 199 of file sbpl_params.h.

Definition at line 205 of file sbpl_params.h.

Definition at line 175 of file sbpl_params.h.

Definition at line 176 of file sbpl_params.h.

add the h_rpy & h_xyz together

Definition at line 95 of file sbpl_params.h.

Definition at line 187 of file sbpl_params.h.

call the orientation solver twice (try rotating the wrist clockwise and then counter-clockwise)

Definition at line 155 of file sbpl_params.h.

plan to a 6D pose goal (if false, plans to 3D goal {x,y,z})

Definition at line 92 of file sbpl_params.h.

use a 3D dijkstra search as the heuristic

Definition at line 83 of file sbpl_params.h.

use IK to try to satisfy the orientation constraint

Definition at line 89 of file sbpl_params.h.

enable multi-resolution motion primitives

Definition at line 80 of file sbpl_params.h.

use the orientation solver to try to satisfy orientation constraint

Definition at line 86 of file sbpl_params.h.

use the elbow heuristic

Definition at line 158 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 99 of file sbpl_params.h.

spew out all debugging text

Definition at line 102 of file sbpl_params.h.

spew out all collision checking related debugging text

Definition at line 108 of file sbpl_params.h.

spew out all heuristic related debugging text

Definition at line 105 of file sbpl_params.h.

Definition at line 182 of file sbpl_params.h.


The documentation for this class was generated from the following file:


sbpl_interface
Author(s): Gil Jones
autogenerated on Sun Jan 17 2016 12:57:04