Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
Planner3dNode Class Reference

Classes

class  CostCoeff
 

Public Types

using Astar = GridAstar< 3, 2 >
 

Public Member Functions

 Planner3dNode ()
 
void spin ()
 

Protected Types

enum  DebugMode { DEBUG_HYSTERESIS, DEBUG_COST_ESTIM }
 
using Planner3DActionServer = actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction >
 

Protected Member Functions

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 ()
 

Protected Attributes

std::shared_ptr< Planner3DActionServeract_
 
float angle_resolution_aspect_
 
Astar as_
 
CostCoeff cc_
 
Astar::Gridmap< char, 0x40 > cm_
 
Astar::Gridmap< char, 0x40 > cm_base_
 
Astar::Gridmap< char, 0x40 > cm_hist_
 
Astar::Gridmap< bbf::BinaryBayesFilter, 0x20 > cm_hist_bbf_
 
Astar::Gridmap< char, 0x80 > cm_hyst_
 
Astar::Gridmap< char, 0x80 > cm_rough_
 
Astar::Gridmap< char, 0x80 > cm_rough_base_
 
int cnt_stuck_
 
Astar::Gridmap< float > cost_estim_cache_
 
ros::Duration costmap_watchdog_
 
DebugMode debug_out_
 
diagnostic_updater::Updater diag_updater_
 
Astar::Vecf ec_
 
Astar::Vecf ec_rough_
 
int esc_angle_
 
int esc_range_
 
double esc_range_f_
 
bool escaping_
 
Astar::Vecf euclid_cost_coef_
 
bool fast_map_update_
 
bool find_best_
 
bool force_goal_orientation_
 
float freq_
 
float freq_min_
 
geometry_msgs::PoseStamped goal_
 
geometry_msgs::PoseStamped goal_raw_
 
int goal_tolerance_ang_
 
double goal_tolerance_ang_f_
 
double goal_tolerance_ang_finish_
 
int goal_tolerance_lin_
 
double goal_tolerance_lin_f_
 
bool goal_updated_
 
bool has_goal_
 
bool has_map_
 
bool has_start_
 
int hist_ignore_range_
 
double hist_ignore_range_f_
 
int hist_ignore_range_max_
 
double hist_ignore_range_max_f_
 
JumpDetector jump_
 
ros::Time last_costmap_
 
int local_range_
 
double local_range_f_
 
int longcut_range_
 
double longcut_range_f_
 
std_msgs::Header map_header_
 
costmap_cspace_msgs::MapMetaData3D map_info_
 
float max_ang_vel_
 
int max_retry_num_
 
float max_vel_
 
float min_curve_raduis_
 
MotionCache motion_cache_
 
MotionCache motion_cache_linear_
 
ros::NodeHandle nh_
 
int num_task_
 
bool overwrite_cost_
 
PathInterpolator path_interpolator_
 
ros::NodeHandle pnh_
 
ros::Publisher pub_debug_
 
ros::Publisher pub_end_
 
ros::Publisher pub_hist_
 
ros::Publisher pub_path_
 
ros::Publisher pub_path_poses_
 
ros::Publisher pub_path_velocity_
 
ros::Publisher pub_start_
 
ros::Publisher pub_status_
 
int range_
 
float remember_hit_odds_
 
float remember_miss_odds_
 
bool remember_updates_
 
Astar::Vecf resolution_
 
std::string robot_frame_
 
RotationCache rot_cache_
 
bool rough_
 
float rough_cost_max_
 
std::vector< Astar::Vecsearch_list_
 
std::vector< Astar::Vecsearch_list_rough_
 
float search_range_
 
ros::ServiceServer srs_forget_
 
ros::ServiceServer srs_make_plan_
 
geometry_msgs::PoseStamped start_
 
planner_cspace_msgs::PlannerStatus status_
 
ros::Subscriber sub_goal_
 
ros::Subscriber sub_map_
 
ros::Subscriber sub_map_update_
 
float sw_wait_
 
bool temporary_escape_
 
tf2_ros::Buffer tfbuf_
 
tf2_ros::TransformListener tfl_
 
int tolerance_angle_
 
double tolerance_angle_f_
 
int tolerance_range_
 
double tolerance_range_f_
 
int unknown_cost_
 
bool use_path_with_velocity_
 

Detailed Description

Definition at line 71 of file planner_3d.cpp.

Member Typedef Documentation

Definition at line 74 of file planner_3d.cpp.

using Planner3dNode::Planner3DActionServer = actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction>
protected

Definition at line 77 of file planner_3d.cpp.

Member Enumeration Documentation

enum Planner3dNode::DebugMode
protected
Enumerator
DEBUG_HYSTERESIS 
DEBUG_COST_ESTIM 

Definition at line 211 of file planner_3d.cpp.

Constructor & Destructor Documentation

Planner3dNode::Planner3dNode ( )
inline

Definition at line 1156 of file planner_3d.cpp.

Member Function Documentation

void Planner3dNode::cbAction ( )
inlineprotected

Definition at line 1121 of file planner_3d.cpp.

float Planner3dNode::cbCost ( const Astar::Vec s,
Astar::Vec e,
const Astar::Vec v_goal,
const Astar::Vec v_start,
const bool  hyst 
)
inlineprotected

Definition at line 1718 of file planner_3d.cpp.

float Planner3dNode::cbCostEstim ( const Astar::Vec s,
const Astar::Vec e 
)
inlineprotected

Definition at line 1670 of file planner_3d.cpp.

bool Planner3dNode::cbForget ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
)
inlineprotected

Definition at line 239 of file planner_3d.cpp.

void Planner3dNode::cbGoal ( const geometry_msgs::PoseStamped::ConstPtr &  msg)
inlineprotected

Definition at line 370 of file planner_3d.cpp.

bool Planner3dNode::cbMakePlan ( nav_msgs::GetPlan::Request &  req,
nav_msgs::GetPlan::Response &  res 
)
inlineprotected

Definition at line 248 of file planner_3d.cpp.

void Planner3dNode::cbMap ( const costmap_cspace_msgs::CSpace3D::ConstPtr &  msg)
inlineprotected

Definition at line 977 of file planner_3d.cpp.

void Planner3dNode::cbMapUpdate ( const costmap_cspace_msgs::CSpace3DUpdate::ConstPtr &  msg)
inlineprotected

Definition at line 744 of file planner_3d.cpp.

void Planner3dNode::cbPreempt ( )
inlineprotected

Definition at line 379 of file planner_3d.cpp.

bool Planner3dNode::cbProgress ( const std::list< Astar::Vec > &  path_grid)
inlineprotected

Definition at line 1663 of file planner_3d.cpp.

std::vector<Astar::Vec>& Planner3dNode::cbSearch ( const Astar::Vec p,
const Astar::Vec s,
const Astar::Vec e 
)
inlineprotected

Definition at line 1647 of file planner_3d.cpp.

void Planner3dNode::diagnoseStatus ( diagnostic_updater::DiagnosticStatusWrapper stat)
inlineprotected

Definition at line 1879 of file planner_3d.cpp.

float Planner3dNode::euclidCost ( const Astar::Vec v,
const Astar::Vecf  coef 
) const
inlineprotected

Definition at line 111 of file planner_3d.cpp.

float Planner3dNode::euclidCost ( const Astar::Vec v) const
inlineprotected

Definition at line 127 of file planner_3d.cpp.

void Planner3dNode::fillCostmap ( reservable_priority_queue< Astar::PriorityVec > &  open,
Astar::Gridmap< float > &  g,
const Astar::Vec s,
const Astar::Vec e 
)
inlineprotected

Definition at line 424 of file planner_3d.cpp.

bool Planner3dNode::makePlan ( const geometry_msgs::Pose gs,
const geometry_msgs::Pose ge,
nav_msgs::Path &  path,
bool  hyst 
)
inlineprotected

Definition at line 1450 of file planner_3d.cpp.

void Planner3dNode::publishCostmap ( )
inlineprotected

Definition at line 683 of file planner_3d.cpp.

void Planner3dNode::publishEmptyPath ( )
inlineprotected

Definition at line 727 of file planner_3d.cpp.

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

Definition at line 544 of file planner_3d.cpp.

bool Planner3dNode::setGoal ( const geometry_msgs::PoseStamped &  msg)
inlineprotected

Definition at line 386 of file planner_3d.cpp.

void Planner3dNode::spin ( )
inline

Definition at line 1313 of file planner_3d.cpp.

bool Planner3dNode::switchDetect ( const nav_msgs::Path &  path)
inlineprotected

Definition at line 1684 of file planner_3d.cpp.

bool Planner3dNode::updateGoal ( const bool  goal_changed = true)
inlineprotected

Definition at line 595 of file planner_3d.cpp.

void Planner3dNode::updateStart ( )
inlineprotected

Definition at line 1128 of file planner_3d.cpp.

Member Data Documentation

std::shared_ptr<Planner3DActionServer> Planner3dNode::act_
protected

Definition at line 95 of file planner_3d.cpp.

float Planner3dNode::angle_resolution_aspect_
protected

Definition at line 209 of file planner_3d.cpp.

Astar Planner3dNode::as_
protected

Definition at line 99 of file planner_3d.cpp.

CostCoeff Planner3dNode::cc_
protected

Definition at line 196 of file planner_3d.cpp.

Astar::Gridmap<char, 0x40> Planner3dNode::cm_
protected

Definition at line 100 of file planner_3d.cpp.

Astar::Gridmap<char, 0x40> Planner3dNode::cm_base_
protected

Definition at line 104 of file planner_3d.cpp.

Astar::Gridmap<char, 0x40> Planner3dNode::cm_hist_
protected

Definition at line 102 of file planner_3d.cpp.

Astar::Gridmap<bbf::BinaryBayesFilter, 0x20> Planner3dNode::cm_hist_bbf_
protected

Definition at line 101 of file planner_3d.cpp.

Astar::Gridmap<char, 0x80> Planner3dNode::cm_hyst_
protected

Definition at line 106 of file planner_3d.cpp.

Astar::Gridmap<char, 0x80> Planner3dNode::cm_rough_
protected

Definition at line 103 of file planner_3d.cpp.

Astar::Gridmap<char, 0x80> Planner3dNode::cm_rough_base_
protected

Definition at line 105 of file planner_3d.cpp.

int Planner3dNode::cnt_stuck_
protected

Definition at line 230 of file planner_3d.cpp.

Astar::Gridmap<float> Planner3dNode::cost_estim_cache_
protected

Definition at line 107 of file planner_3d.cpp.

ros::Duration Planner3dNode::costmap_watchdog_
protected

Definition at line 236 of file planner_3d.cpp.

DebugMode Planner3dNode::debug_out_
protected

Definition at line 216 of file planner_3d.cpp.

diagnostic_updater::Updater Planner3dNode::diag_updater_
protected

Definition at line 235 of file planner_3d.cpp.

Astar::Vecf Planner3dNode::ec_
protected

Definition at line 201 of file planner_3d.cpp.

Astar::Vecf Planner3dNode::ec_rough_
protected

Definition at line 202 of file planner_3d.cpp.

int Planner3dNode::esc_angle_
protected

Definition at line 148 of file planner_3d.cpp.

int Planner3dNode::esc_range_
protected

Definition at line 147 of file planner_3d.cpp.

double Planner3dNode::esc_range_f_
protected

Definition at line 149 of file planner_3d.cpp.

bool Planner3dNode::escaping_
protected

Definition at line 228 of file planner_3d.cpp.

Astar::Vecf Planner3dNode::euclid_cost_coef_
protected

Definition at line 109 of file planner_3d.cpp.

bool Planner3dNode::fast_map_update_
protected

Definition at line 161 of file planner_3d.cpp.

bool Planner3dNode::find_best_
protected

Definition at line 220 of file planner_3d.cpp.

bool Planner3dNode::force_goal_orientation_
protected

Definition at line 226 of file planner_3d.cpp.

float Planner3dNode::freq_
protected

Definition at line 139 of file planner_3d.cpp.

float Planner3dNode::freq_min_
protected

Definition at line 140 of file planner_3d.cpp.

geometry_msgs::PoseStamped Planner3dNode::goal_
protected

Definition at line 199 of file planner_3d.cpp.

geometry_msgs::PoseStamped Planner3dNode::goal_raw_
protected

Definition at line 200 of file planner_3d.cpp.

int Planner3dNode::goal_tolerance_ang_
protected

Definition at line 208 of file planner_3d.cpp.

double Planner3dNode::goal_tolerance_ang_f_
protected

Definition at line 205 of file planner_3d.cpp.

double Planner3dNode::goal_tolerance_ang_finish_
protected

Definition at line 206 of file planner_3d.cpp.

int Planner3dNode::goal_tolerance_lin_
protected

Definition at line 207 of file planner_3d.cpp.

double Planner3dNode::goal_tolerance_lin_f_
protected

Definition at line 204 of file planner_3d.cpp.

bool Planner3dNode::goal_updated_
protected

Definition at line 159 of file planner_3d.cpp.

bool Planner3dNode::has_goal_
protected

Definition at line 157 of file planner_3d.cpp.

bool Planner3dNode::has_map_
protected

Definition at line 156 of file planner_3d.cpp.

bool Planner3dNode::has_start_
protected

Definition at line 158 of file planner_3d.cpp.

int Planner3dNode::hist_ignore_range_
protected

Definition at line 165 of file planner_3d.cpp.

double Planner3dNode::hist_ignore_range_f_
protected

Definition at line 164 of file planner_3d.cpp.

int Planner3dNode::hist_ignore_range_max_
protected

Definition at line 167 of file planner_3d.cpp.

double Planner3dNode::hist_ignore_range_max_f_
protected

Definition at line 166 of file planner_3d.cpp.

JumpDetector Planner3dNode::jump_
protected

Definition at line 174 of file planner_3d.cpp.

ros::Time Planner3dNode::last_costmap_
protected

Definition at line 237 of file planner_3d.cpp.

int Planner3dNode::local_range_
protected

Definition at line 143 of file planner_3d.cpp.

double Planner3dNode::local_range_f_
protected

Definition at line 144 of file planner_3d.cpp.

int Planner3dNode::longcut_range_
protected

Definition at line 145 of file planner_3d.cpp.

double Planner3dNode::longcut_range_f_
protected

Definition at line 146 of file planner_3d.cpp.

std_msgs::Header Planner3dNode::map_header_
protected

Definition at line 136 of file planner_3d.cpp.

costmap_cspace_msgs::MapMetaData3D Planner3dNode::map_info_
protected

Definition at line 135 of file planner_3d.cpp.

float Planner3dNode::max_ang_vel_
protected

Definition at line 138 of file planner_3d.cpp.

int Planner3dNode::max_retry_num_
protected

Definition at line 177 of file planner_3d.cpp.

float Planner3dNode::max_vel_
protected

Definition at line 137 of file planner_3d.cpp.

float Planner3dNode::min_curve_raduis_
protected

Definition at line 172 of file planner_3d.cpp.

MotionCache Planner3dNode::motion_cache_
protected

Definition at line 232 of file planner_3d.cpp.

MotionCache Planner3dNode::motion_cache_linear_
protected

Definition at line 233 of file planner_3d.cpp.

ros::NodeHandle Planner3dNode::nh_
protected

Definition at line 79 of file planner_3d.cpp.

int Planner3dNode::num_task_
protected

Definition at line 179 of file planner_3d.cpp.

bool Planner3dNode::overwrite_cost_
protected

Definition at line 155 of file planner_3d.cpp.

PathInterpolator Planner3dNode::path_interpolator_
protected

Definition at line 133 of file planner_3d.cpp.

ros::NodeHandle Planner3dNode::pnh_
protected

Definition at line 80 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_debug_
protected

Definition at line 87 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_end_
protected

Definition at line 90 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_hist_
protected

Definition at line 88 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_path_
protected

Definition at line 84 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_path_poses_
protected

Definition at line 86 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_path_velocity_
protected

Definition at line 85 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_start_
protected

Definition at line 89 of file planner_3d.cpp.

ros::Publisher Planner3dNode::pub_status_
protected

Definition at line 91 of file planner_3d.cpp.

int Planner3dNode::range_
protected

Definition at line 142 of file planner_3d.cpp.

float Planner3dNode::remember_hit_odds_
protected

Definition at line 169 of file planner_3d.cpp.

float Planner3dNode::remember_miss_odds_
protected

Definition at line 170 of file planner_3d.cpp.

bool Planner3dNode::remember_updates_
protected

Definition at line 160 of file planner_3d.cpp.

Astar::Vecf Planner3dNode::resolution_
protected

Definition at line 203 of file planner_3d.cpp.

std::string Planner3dNode::robot_frame_
protected

Definition at line 175 of file planner_3d.cpp.

RotationCache Planner3dNode::rot_cache_
protected

Definition at line 132 of file planner_3d.cpp.

bool Planner3dNode::rough_
protected

Definition at line 224 of file planner_3d.cpp.

float Planner3dNode::rough_cost_max_
protected

Definition at line 223 of file planner_3d.cpp.

std::vector<Astar::Vec> Planner3dNode::search_list_
protected

Definition at line 162 of file planner_3d.cpp.

std::vector<Astar::Vec> Planner3dNode::search_list_rough_
protected

Definition at line 163 of file planner_3d.cpp.

float Planner3dNode::search_range_
protected

Definition at line 141 of file planner_3d.cpp.

ros::ServiceServer Planner3dNode::srs_forget_
protected

Definition at line 92 of file planner_3d.cpp.

ros::ServiceServer Planner3dNode::srs_make_plan_
protected

Definition at line 93 of file planner_3d.cpp.

geometry_msgs::PoseStamped Planner3dNode::start_
protected

Definition at line 198 of file planner_3d.cpp.

planner_cspace_msgs::PlannerStatus Planner3dNode::status_
protected

Definition at line 218 of file planner_3d.cpp.

ros::Subscriber Planner3dNode::sub_goal_
protected

Definition at line 83 of file planner_3d.cpp.

ros::Subscriber Planner3dNode::sub_map_
protected

Definition at line 81 of file planner_3d.cpp.

ros::Subscriber Planner3dNode::sub_map_update_
protected

Definition at line 82 of file planner_3d.cpp.

float Planner3dNode::sw_wait_
protected

Definition at line 221 of file planner_3d.cpp.

bool Planner3dNode::temporary_escape_
protected

Definition at line 168 of file planner_3d.cpp.

tf2_ros::Buffer Planner3dNode::tfbuf_
protected

Definition at line 96 of file planner_3d.cpp.

tf2_ros::TransformListener Planner3dNode::tfl_
protected

Definition at line 97 of file planner_3d.cpp.

int Planner3dNode::tolerance_angle_
protected

Definition at line 151 of file planner_3d.cpp.

double Planner3dNode::tolerance_angle_f_
protected

Definition at line 153 of file planner_3d.cpp.

int Planner3dNode::tolerance_range_
protected

Definition at line 150 of file planner_3d.cpp.

double Planner3dNode::tolerance_range_f_
protected

Definition at line 152 of file planner_3d.cpp.

int Planner3dNode::unknown_cost_
protected

Definition at line 154 of file planner_3d.cpp.

bool Planner3dNode::use_path_with_velocity_
protected

Definition at line 171 of file planner_3d.cpp.


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


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:14