#include <ScavTaskFetchObject.h>
Public Member Functions | |
void | executeTask (int timeout, TaskResult &result, std::string &record) |
void | hriThread () |
void | motionThread () |
ScavTaskFetchObject () | |
ScavTaskFetchObject (ros::NodeHandle *node_handle, std::string path_of_dir) | |
void | stopEarly () |
~ScavTaskFetchObject () | |
Public Attributes | |
std::string | directory |
ros::ServiceClient * | gui_service_client |
std::string | object_name |
bool | random_walk_flag |
std::string | room_name_from |
std::string | room_name_to |
SearchPlannerSimple * | search_planner_simple |
bool | target_detected |
bool | task_completed |
Private Attributes | |
bool | _target_detected |
Definition at line 16 of file ScavTaskFetchObject.h.
ScavTaskFetchObject::~ScavTaskFetchObject | ( | ) | [inline] |
Definition at line 20 of file ScavTaskFetchObject.h.
ScavTaskFetchObject::ScavTaskFetchObject | ( | ros::NodeHandle * | node_handle, |
std::string | path_of_dir | ||
) |
Definition at line 12 of file ScavTaskFetchObject.cpp.
void ScavTaskFetchObject::executeTask | ( | int | timeout, |
TaskResult & | result, | ||
std::string & | record | ||
) | [virtual] |
Implements ScavTask.
Definition at line 23 of file ScavTaskFetchObject.cpp.
void ScavTaskFetchObject::hriThread | ( | ) |
Definition at line 66 of file ScavTaskFetchObject.cpp.
void ScavTaskFetchObject::motionThread | ( | ) |
Definition at line 49 of file ScavTaskFetchObject.cpp.
void ScavTaskFetchObject::stopEarly | ( | ) | [virtual] |
Implements ScavTask.
Definition at line 175 of file ScavTaskFetchObject.cpp.
bool ScavTaskFetchObject::_target_detected [private] |
Definition at line 42 of file ScavTaskFetchObject.h.
std::string ScavTaskFetchObject::directory |
Definition at line 37 of file ScavTaskFetchObject.h.
Definition at line 39 of file ScavTaskFetchObject.h.
std::string ScavTaskFetchObject::object_name |
Definition at line 35 of file ScavTaskFetchObject.h.
Definition at line 29 of file ScavTaskFetchObject.h.
std::string ScavTaskFetchObject::room_name_from |
Definition at line 35 of file ScavTaskFetchObject.h.
std::string ScavTaskFetchObject::room_name_to |
Definition at line 35 of file ScavTaskFetchObject.h.
Definition at line 33 of file ScavTaskFetchObject.h.
Definition at line 30 of file ScavTaskFetchObject.h.
Definition at line 31 of file ScavTaskFetchObject.h.