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