#include <PilotConfig.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 PilotConfig &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 PilotConfig & | __getDefault__ () |
static const dynamic_reconfigure::ConfigDescription & | __getDescriptionMessage__ () |
static const PilotConfig & | __getMax__ () |
static const PilotConfig & | __getMin__ () |
static const std::vector < AbstractParamDescriptionConstPtr > & | __getParamDescriptions__ () |
Public Attributes | |
int | acceleration_controller |
double | brake_hold |
double | brake_kd |
double | brake_ki |
double | brake_kp |
bool | human_steering |
double | limit_forward |
double | limit_reverse |
double | throttle_kd |
double | throttle_ki |
double | throttle_kp |
double | timeout |
Static Private Member Functions | |
static const PilotConfigStatics * | __get_statics__ () |
Definition at line 59 of file PilotConfig.h.
typedef boost::shared_ptr<const AbstractParamDescription> art_pilot::PilotConfig::AbstractParamDescriptionConstPtr |
Definition at line 84 of file PilotConfig.h.
typedef boost::shared_ptr<AbstractParamDescription> art_pilot::PilotConfig::AbstractParamDescriptionPtr |
Definition at line 83 of file PilotConfig.h.
void art_pilot::PilotConfig::__clamp__ | ( | ) | [inline] |
Definition at line 218 of file PilotConfig.h.
bool art_pilot::PilotConfig::__fromMessage__ | ( | dynamic_reconfigure::Config & | msg | ) | [inline] |
Definition at line 160 of file PilotConfig.h.
void art_pilot::PilotConfig::__fromServer__ | ( | const ros::NodeHandle & | nh | ) | [inline] |
Definition at line 211 of file PilotConfig.h.
const PilotConfigStatics * art_pilot::PilotConfig::__get_statics__ | ( | ) | [inline, static, private] |
Definition at line 403 of file PilotConfig.h.
const PilotConfig & art_pilot::PilotConfig::__getDefault__ | ( | ) | [inline, static] |
Definition at line 383 of file PilotConfig.h.
const dynamic_reconfigure::ConfigDescription & art_pilot::PilotConfig::__getDescriptionMessage__ | ( | ) | [inline, static] |
Definition at line 378 of file PilotConfig.h.
const PilotConfig & art_pilot::PilotConfig::__getMax__ | ( | ) | [inline, static] |
Definition at line 388 of file PilotConfig.h.
const PilotConfig & art_pilot::PilotConfig::__getMin__ | ( | ) | [inline, static] |
Definition at line 393 of file PilotConfig.h.
const std::vector< PilotConfig::AbstractParamDescriptionConstPtr > & art_pilot::PilotConfig::__getParamDescriptions__ | ( | ) | [inline, static] |
Definition at line 398 of file PilotConfig.h.
uint32_t art_pilot::PilotConfig::__level__ | ( | const PilotConfig & | config | ) | const [inline] |
Definition at line 227 of file PilotConfig.h.
void art_pilot::PilotConfig::__toMessage__ | ( | dynamic_reconfigure::Config & | msg | ) | const [inline] |
Definition at line 198 of file PilotConfig.h.
void art_pilot::PilotConfig::__toMessage__ | ( | dynamic_reconfigure::Config & | msg, | |
const std::vector< AbstractParamDescriptionConstPtr > & | __param_descriptions__ | |||
) | const [inline] |
Definition at line 191 of file PilotConfig.h.
void art_pilot::PilotConfig::__toServer__ | ( | const ros::NodeHandle & | nh | ) | const [inline] |
Definition at line 204 of file PilotConfig.h.
Definition at line 135 of file PilotConfig.h.
Definition at line 137 of file PilotConfig.h.
Definition at line 151 of file PilotConfig.h.
Definition at line 149 of file PilotConfig.h.
Definition at line 147 of file PilotConfig.h.
Definition at line 139 of file PilotConfig.h.
Definition at line 141 of file PilotConfig.h.
Definition at line 143 of file PilotConfig.h.
Definition at line 157 of file PilotConfig.h.
Definition at line 155 of file PilotConfig.h.
Definition at line 153 of file PilotConfig.h.
Definition at line 145 of file PilotConfig.h.