|
void | cbAction () |
|
float | cbCost (const Astar::Vec &s, Astar::Vec &e, const Astar::Vec &v_goal, const Astar::Vec &v_start, const bool hyst) |
|
float | cbCostEstim (const Astar::Vec &s, const Astar::Vec &e) |
|
bool | cbForget (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
|
void | cbGoal (const geometry_msgs::PoseStamped::ConstPtr &msg) |
|
bool | cbMakePlan (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res) |
|
void | cbMap (const costmap_cspace_msgs::CSpace3D::ConstPtr &msg) |
|
void | cbMapUpdate (const costmap_cspace_msgs::CSpace3DUpdate::ConstPtr &msg) |
|
void | cbPreempt () |
|
bool | cbProgress (const std::list< Astar::Vec > &path_grid) |
|
std::vector< Astar::Vec > & | cbSearch (const Astar::Vec &p, const Astar::Vec &s, const Astar::Vec &e) |
|
void | diagnoseStatus (diagnostic_updater::DiagnosticStatusWrapper &stat) |
|
float | euclidCost (const Astar::Vec &v, const Astar::Vecf coef) const |
|
float | euclidCost (const Astar::Vec &v) const |
|
void | fillCostmap (reservable_priority_queue< Astar::PriorityVec > &open, Astar::Gridmap< float > &g, const Astar::Vec &s, const Astar::Vec &e) |
|
bool | makePlan (const geometry_msgs::Pose &gs, const geometry_msgs::Pose &ge, nav_msgs::Path &path, bool hyst) |
|
void | publishCostmap () |
|
void | publishEmptyPath () |
|
bool | searchAvailablePos (Astar::Vec &s, const int xy_range, const int angle_range, const int cost_acceptable=50, const int min_xy_range=0) |
|
bool | setGoal (const geometry_msgs::PoseStamped &msg) |
|
bool | switchDetect (const nav_msgs::Path &path) |
|
bool | updateGoal (const bool goal_changed=true) |
|
void | updateStart () |
|
Definition at line 71 of file planner_3d.cpp.
Enumerator |
---|
DEBUG_HYSTERESIS |
|
DEBUG_COST_ESTIM |
|
Definition at line 211 of file planner_3d.cpp.
Planner3dNode::Planner3dNode |
( |
| ) |
|
|
inline |
void Planner3dNode::cbAction |
( |
| ) |
|
|
inlineprotected |
bool Planner3dNode::cbForget |
( |
std_srvs::EmptyRequest & |
req, |
|
|
std_srvs::EmptyResponse & |
res |
|
) |
| |
|
inlineprotected |
void Planner3dNode::cbGoal |
( |
const geometry_msgs::PoseStamped::ConstPtr & |
msg | ) |
|
|
inlineprotected |
bool Planner3dNode::cbMakePlan |
( |
nav_msgs::GetPlan::Request & |
req, |
|
|
nav_msgs::GetPlan::Response & |
res |
|
) |
| |
|
inlineprotected |
void Planner3dNode::cbMap |
( |
const costmap_cspace_msgs::CSpace3D::ConstPtr & |
msg | ) |
|
|
inlineprotected |
void Planner3dNode::cbMapUpdate |
( |
const costmap_cspace_msgs::CSpace3DUpdate::ConstPtr & |
msg | ) |
|
|
inlineprotected |
void Planner3dNode::cbPreempt |
( |
| ) |
|
|
inlineprotected |
bool Planner3dNode::cbProgress |
( |
const std::list< Astar::Vec > & |
path_grid | ) |
|
|
inlineprotected |
float Planner3dNode::euclidCost |
( |
const Astar::Vec & |
v | ) |
const |
|
inlineprotected |
void Planner3dNode::publishCostmap |
( |
| ) |
|
|
inlineprotected |
void Planner3dNode::publishEmptyPath |
( |
| ) |
|
|
inlineprotected |
bool Planner3dNode::searchAvailablePos |
( |
Astar::Vec & |
s, |
|
|
const int |
xy_range, |
|
|
const int |
angle_range, |
|
|
const int |
cost_acceptable = 50 , |
|
|
const int |
min_xy_range = 0 |
|
) |
| |
|
inlineprotected |
bool Planner3dNode::setGoal |
( |
const geometry_msgs::PoseStamped & |
msg | ) |
|
|
inlineprotected |
void Planner3dNode::spin |
( |
| ) |
|
|
inline |
bool Planner3dNode::switchDetect |
( |
const nav_msgs::Path & |
path | ) |
|
|
inlineprotected |
bool Planner3dNode::updateGoal |
( |
const bool |
goal_changed = true | ) |
|
|
inlineprotected |
void Planner3dNode::updateStart |
( |
| ) |
|
|
inlineprotected |
float Planner3dNode::angle_resolution_aspect_ |
|
protected |
Astar::Gridmap<char, 0x40> Planner3dNode::cm_ |
|
protected |
Astar::Gridmap<char, 0x40> Planner3dNode::cm_base_ |
|
protected |
Astar::Gridmap<char, 0x40> Planner3dNode::cm_hist_ |
|
protected |
Astar::Gridmap<char, 0x80> Planner3dNode::cm_hyst_ |
|
protected |
Astar::Gridmap<char, 0x80> Planner3dNode::cm_rough_ |
|
protected |
Astar::Gridmap<char, 0x80> Planner3dNode::cm_rough_base_ |
|
protected |
int Planner3dNode::cnt_stuck_ |
|
protected |
Astar::Gridmap<float> Planner3dNode::cost_estim_cache_ |
|
protected |
int Planner3dNode::esc_angle_ |
|
protected |
int Planner3dNode::esc_range_ |
|
protected |
double Planner3dNode::esc_range_f_ |
|
protected |
bool Planner3dNode::escaping_ |
|
protected |
bool Planner3dNode::fast_map_update_ |
|
protected |
bool Planner3dNode::find_best_ |
|
protected |
bool Planner3dNode::force_goal_orientation_ |
|
protected |
float Planner3dNode::freq_ |
|
protected |
float Planner3dNode::freq_min_ |
|
protected |
geometry_msgs::PoseStamped Planner3dNode::goal_ |
|
protected |
geometry_msgs::PoseStamped Planner3dNode::goal_raw_ |
|
protected |
int Planner3dNode::goal_tolerance_ang_ |
|
protected |
double Planner3dNode::goal_tolerance_ang_f_ |
|
protected |
double Planner3dNode::goal_tolerance_ang_finish_ |
|
protected |
int Planner3dNode::goal_tolerance_lin_ |
|
protected |
double Planner3dNode::goal_tolerance_lin_f_ |
|
protected |
bool Planner3dNode::goal_updated_ |
|
protected |
bool Planner3dNode::has_goal_ |
|
protected |
bool Planner3dNode::has_map_ |
|
protected |
bool Planner3dNode::has_start_ |
|
protected |
int Planner3dNode::hist_ignore_range_ |
|
protected |
double Planner3dNode::hist_ignore_range_f_ |
|
protected |
int Planner3dNode::hist_ignore_range_max_ |
|
protected |
double Planner3dNode::hist_ignore_range_max_f_ |
|
protected |
int Planner3dNode::local_range_ |
|
protected |
double Planner3dNode::local_range_f_ |
|
protected |
int Planner3dNode::longcut_range_ |
|
protected |
double Planner3dNode::longcut_range_f_ |
|
protected |
costmap_cspace_msgs::MapMetaData3D Planner3dNode::map_info_ |
|
protected |
float Planner3dNode::max_ang_vel_ |
|
protected |
int Planner3dNode::max_retry_num_ |
|
protected |
float Planner3dNode::max_vel_ |
|
protected |
float Planner3dNode::min_curve_raduis_ |
|
protected |
int Planner3dNode::num_task_ |
|
protected |
bool Planner3dNode::overwrite_cost_ |
|
protected |
int Planner3dNode::range_ |
|
protected |
float Planner3dNode::remember_hit_odds_ |
|
protected |
float Planner3dNode::remember_miss_odds_ |
|
protected |
bool Planner3dNode::remember_updates_ |
|
protected |
std::string Planner3dNode::robot_frame_ |
|
protected |
bool Planner3dNode::rough_ |
|
protected |
float Planner3dNode::rough_cost_max_ |
|
protected |
std::vector<Astar::Vec> Planner3dNode::search_list_ |
|
protected |
std::vector<Astar::Vec> Planner3dNode::search_list_rough_ |
|
protected |
float Planner3dNode::search_range_ |
|
protected |
geometry_msgs::PoseStamped Planner3dNode::start_ |
|
protected |
planner_cspace_msgs::PlannerStatus Planner3dNode::status_ |
|
protected |
float Planner3dNode::sw_wait_ |
|
protected |
bool Planner3dNode::temporary_escape_ |
|
protected |
int Planner3dNode::tolerance_angle_ |
|
protected |
double Planner3dNode::tolerance_angle_f_ |
|
protected |
int Planner3dNode::tolerance_range_ |
|
protected |
double Planner3dNode::tolerance_range_f_ |
|
protected |
int Planner3dNode::unknown_cost_ |
|
protected |
bool Planner3dNode::use_path_with_velocity_ |
|
protected |
The documentation for this class was generated from the following file: