Classes | |
class | Edge |
class | Graph |
class | GraphVis |
class | Node |
class | Task |
Public Member Functions | |
void | CachePlan (const ast::point_t &start, const ast::point_t &goal, Graph *graph) |
void | Dock () |
void | Dock () |
void | Enable (Stg::Model *model, bool &sub, bool on) |
void | EnableFiducial (bool on) |
void | EnableLaser (bool on) |
void | EnableSonar (bool on) |
bool | Full () |
bool | Full () |
bool | Hungry () |
bool | Hungry () |
Graph * | LookupPlan (const ast::point_t &start, const ast::point_t &goal) |
bool | ObstacleAvoid () |
bool | ObstacleAvoid () |
void | Plan (Pose sp) |
uint64_t | Pt64 (const ast::point_t &pt) |
Robot (ModelPosition *pos, Model *source, Model *sink) | |
Robot (ModelPosition *pos, Model *fuel, Model *pool) | |
void | SetGoal (Model *goal) |
void | SetTask (unsigned int t) |
void | UnDock () |
void | UnDock () |
int | Update (void) |
void | Work () |
void | Work () |
Static Public Member Functions | |
static int | FiducialUpdate (ModelFiducial *mod, Robot *robot) |
static int | FlagDecr (Model *mod, Robot *robot) |
static int | FlagIncr (Model *mod, Robot *robot) |
static int | LaserUpdate (ModelRanger *laser, Robot *robot) |
static int | PositionUpdate (ModelPosition *pos, Robot *robot) |
static int | UpdateCallback (ModelRanger *laser, Robot *robot) |
Public Attributes | |
Stg::ModelPosition * | position |
Stg::ModelRanger * | ranger |
Static Public Attributes | |
static std::map< std::pair< uint64_t, uint64_t >, Graph * > | plancache |
static std::vector< Task > | tasks |
Private Types | |
enum | { MODE_WORK =0, MODE_DOCK, MODE_UNDOCK, MODE_QUEUE } |
Private Attributes | |
bool | at_dest |
int | avoidcount |
Pose | cached_goal_pose |
bool | charger_ahoy |
double | charger_bearing |
double | charger_heading |
double | charger_range |
radians_t | docked_angle |
ModelFiducial * | fiducial |
bool | fiducial_sub |
bool | force_recharge |
Model * | fuel_zone |
Model * | goal |
Graph * | graphp |
GraphVis | graphvis |
ModelRanger * | laser |
bool | laser_sub |
nav_mode_t | mode |
enum Robot:: { ... } | mode |
unsigned int | node_interval |
unsigned int | node_interval_countdown |
Model * | pool_zone |
ModelPosition * | pos |
int | randcount |
ModelRanger * | ranger |
Model * | sink |
ModelRanger * | sonar |
bool | sonar_sub |
Model * | source |
unsigned int | task |
long int | wait_started_at |
int | work_get |
int | work_put |
Static Private Attributes | |
static uint8_t * | map_data |
static const unsigned int | map_height |
static Model * | map_model |
static const unsigned int | map_width |
static pthread_mutex_t | planner_mutex = PTHREAD_MUTEX_INITIALIZER |
|
private |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlinestatic |
|
inlinestatic |
|
inline |
|
inlinestatic |
|
inline |
|
inlinestatic |
|
private |
|
private |
|
private |
enum { ... } Robot::mode |
|
static |
|
staticprivate |
|
private |
Stg::ModelPosition* Robot::position |
Stg::ModelRanger* Robot::ranger |
|
private |
|
private |
|
static |