#include <DWAPlannerConfig.h>
Classes | |
class | AbstractParamDescription |
class | ParamDescription |
Public Types | |
typedef boost::shared_ptr < const AbstractParamDescription > | AbstractParamDescriptionConstPtr |
typedef boost::shared_ptr < AbstractParamDescription > | AbstractParamDescriptionPtr |
Public Member Functions | |
void | __clamp__ () |
bool | __fromMessage__ (dynamic_reconfigure::Config &msg) |
void | __fromServer__ (const ros::NodeHandle &nh) |
uint32_t | __level__ (const DWAPlannerConfig &config) const |
void | __toMessage__ (dynamic_reconfigure::Config &msg) const |
void | __toMessage__ (dynamic_reconfigure::Config &msg, const std::vector< AbstractParamDescriptionConstPtr > &__param_descriptions__) const |
void | __toServer__ (const ros::NodeHandle &nh) const |
Static Public Member Functions | |
static const DWAPlannerConfig & | __getDefault__ () |
static const dynamic_reconfigure::ConfigDescription & | __getDescriptionMessage__ () |
static const DWAPlannerConfig & | __getMax__ () |
static const DWAPlannerConfig & | __getMin__ () |
static const std::vector < AbstractParamDescriptionConstPtr > & | __getParamDescriptions__ () |
Public Attributes | |
double | forward_point_distance |
double | goal_distance_bias |
double | max_rot_vel |
double | max_scaling_factor |
double | max_trans_vel |
double | max_vel_x |
double | max_vel_y |
double | min_rot_vel |
double | min_trans_vel |
double | min_vel_x |
double | min_vel_y |
double | occdist_scale |
double | oscillation_reset_dist |
double | path_distance_bias |
bool | penalize_negative_x |
double | scaling_speed |
double | sim_granularity |
double | sim_time |
double | stop_time_buffer |
int | vth_samples |
int | vx_samples |
int | vy_samples |
Static Private Member Functions | |
static const DWAPlannerConfigStatics * | __get_statics__ () |
Definition at line 59 of file DWAPlannerConfig.h.
typedef boost::shared_ptr<const AbstractParamDescription> dwa_local_planner::DWAPlannerConfig::AbstractParamDescriptionConstPtr |
Definition at line 84 of file DWAPlannerConfig.h.
typedef boost::shared_ptr<AbstractParamDescription> dwa_local_planner::DWAPlannerConfig::AbstractParamDescriptionPtr |
Definition at line 83 of file DWAPlannerConfig.h.
void dwa_local_planner::DWAPlannerConfig::__clamp__ | ( | ) | [inline] |
Definition at line 238 of file DWAPlannerConfig.h.
bool dwa_local_planner::DWAPlannerConfig::__fromMessage__ | ( | dynamic_reconfigure::Config & | msg | ) | [inline] |
Definition at line 180 of file DWAPlannerConfig.h.
void dwa_local_planner::DWAPlannerConfig::__fromServer__ | ( | const ros::NodeHandle & | nh | ) | [inline] |
Definition at line 231 of file DWAPlannerConfig.h.
const DWAPlannerConfigStatics * dwa_local_planner::DWAPlannerConfig::__get_statics__ | ( | ) | [inline, static, private] |
Definition at line 503 of file DWAPlannerConfig.h.
const DWAPlannerConfig & dwa_local_planner::DWAPlannerConfig::__getDefault__ | ( | ) | [inline, static] |
Definition at line 483 of file DWAPlannerConfig.h.
const dynamic_reconfigure::ConfigDescription & dwa_local_planner::DWAPlannerConfig::__getDescriptionMessage__ | ( | ) | [inline, static] |
Definition at line 478 of file DWAPlannerConfig.h.
const DWAPlannerConfig & dwa_local_planner::DWAPlannerConfig::__getMax__ | ( | ) | [inline, static] |
Definition at line 488 of file DWAPlannerConfig.h.
const DWAPlannerConfig & dwa_local_planner::DWAPlannerConfig::__getMin__ | ( | ) | [inline, static] |
Definition at line 493 of file DWAPlannerConfig.h.
const std::vector< DWAPlannerConfig::AbstractParamDescriptionConstPtr > & dwa_local_planner::DWAPlannerConfig::__getParamDescriptions__ | ( | ) | [inline, static] |
Definition at line 498 of file DWAPlannerConfig.h.
uint32_t dwa_local_planner::DWAPlannerConfig::__level__ | ( | const DWAPlannerConfig & | config | ) | const [inline] |
Definition at line 247 of file DWAPlannerConfig.h.
void dwa_local_planner::DWAPlannerConfig::__toMessage__ | ( | dynamic_reconfigure::Config & | msg | ) | const [inline] |
Definition at line 218 of file DWAPlannerConfig.h.
void dwa_local_planner::DWAPlannerConfig::__toMessage__ | ( | dynamic_reconfigure::Config & | msg, | |
const std::vector< AbstractParamDescriptionConstPtr > & | __param_descriptions__ | |||
) | const [inline] |
Definition at line 211 of file DWAPlannerConfig.h.
void dwa_local_planner::DWAPlannerConfig::__toServer__ | ( | const ros::NodeHandle & | nh | ) | const [inline] |
Definition at line 224 of file DWAPlannerConfig.h.
Definition at line 165 of file DWAPlannerConfig.h.
Definition at line 157 of file DWAPlannerConfig.h.
Definition at line 147 of file DWAPlannerConfig.h.
Definition at line 169 of file DWAPlannerConfig.h.
Definition at line 135 of file DWAPlannerConfig.h.
Definition at line 139 of file DWAPlannerConfig.h.
Definition at line 143 of file DWAPlannerConfig.h.
Definition at line 149 of file DWAPlannerConfig.h.
Definition at line 137 of file DWAPlannerConfig.h.
Definition at line 141 of file DWAPlannerConfig.h.
Definition at line 145 of file DWAPlannerConfig.h.
Definition at line 159 of file DWAPlannerConfig.h.
Definition at line 163 of file DWAPlannerConfig.h.
Definition at line 155 of file DWAPlannerConfig.h.
Definition at line 177 of file DWAPlannerConfig.h.
Definition at line 167 of file DWAPlannerConfig.h.
Definition at line 153 of file DWAPlannerConfig.h.
Definition at line 151 of file DWAPlannerConfig.h.
Definition at line 161 of file DWAPlannerConfig.h.
Definition at line 175 of file DWAPlannerConfig.h.
Definition at line 171 of file DWAPlannerConfig.h.
Definition at line 173 of file DWAPlannerConfig.h.