#include <semantic_navigator.hpp>
|
bool | cancelMoveBaseGoal () |
|
bool | clearCostmaps () |
|
void | determineNavigationState (int &navi_result, const int move_base_result, const actionlib::SimpleClientGoalState move_base_state) |
|
void | feedbackNavigation (const int status, const double distance, const double remain_time, const std::string message) |
|
bool | getGoalLocation (const std::string location, yocs_msgs::Waypoint &waypoint) |
|
void | goNear (const yocs_msgs::Waypoint waypoint, const double in_distance, const int num_retry, const double timeout) |
|
void | goOn (const yocs_msgs::Waypoint waypoint, const double in_distance, const int num_retry, const double timeout) |
|
void | nextState (bool &retry, bool &final_result, std::string &message, const int navi_result, const ros::Time started_time) |
|
void | processMoveBaseFeedback (const move_base_msgs::MoveBaseFeedback::ConstPtr &feedback, const geometry_msgs::PoseStamped &target) |
|
void | processNavigateToGoal () |
|
void | processNavigation (yocs_msgs::NavigateToGoal::ConstPtr goal) |
|
void | processPreemptNavigateTo () |
|
void | processWaypointList (const yocs_msgs::WaypointList::ConstPtr &msg) |
|
void | terminateNavigation (bool success, const std::string message) |
|
void | waitForMoveBase (int &move_base_result, const ros::Time &start_time, const double timeout) |
|
Definition at line 24 of file semantic_navigator.hpp.
yocs_navigator::SemanticNavigator::SemanticNavigator |
( |
ros::NodeHandle & |
n | ) |
|
yocs_navigator::SemanticNavigator::SemanticNavigator |
( |
ros::NodeHandle & |
n, |
|
|
const std::string & |
as_navigator_topic, |
|
|
const std::string & |
sub_waypointlist_topic |
|
) |
| |
yocs_navigator::SemanticNavigator::~SemanticNavigator |
( |
| ) |
|
|
virtual |
bool yocs_navigator::SemanticNavigator::cancelMoveBaseGoal |
( |
| ) |
|
|
protected |
bool yocs_navigator::SemanticNavigator::clearCostmaps |
( |
| ) |
|
|
protected |
void yocs_navigator::SemanticNavigator::determineNavigationState |
( |
int & |
navi_result, |
|
|
const int |
move_base_result, |
|
|
const actionlib::SimpleClientGoalState |
move_base_state |
|
) |
| |
|
protected |
void yocs_navigator::SemanticNavigator::feedbackNavigation |
( |
const int |
status, |
|
|
const double |
distance, |
|
|
const double |
remain_time, |
|
|
const std::string |
message |
|
) |
| |
|
protected |
bool yocs_navigator::SemanticNavigator::getGoalLocation |
( |
const std::string |
location, |
|
|
yocs_msgs::Waypoint & |
waypoint |
|
) |
| |
|
protected |
void yocs_navigator::SemanticNavigator::goNear |
( |
const yocs_msgs::Waypoint |
waypoint, |
|
|
const double |
in_distance, |
|
|
const int |
num_retry, |
|
|
const double |
timeout |
|
) |
| |
|
protected |
void yocs_navigator::SemanticNavigator::goOn |
( |
const yocs_msgs::Waypoint |
waypoint, |
|
|
const double |
in_distance, |
|
|
const int |
num_retry, |
|
|
const double |
timeout |
|
) |
| |
|
protected |
bool yocs_navigator::SemanticNavigator::init |
( |
| ) |
|
void yocs_navigator::SemanticNavigator::loginfo |
( |
const std::string & |
msg | ) |
|
void yocs_navigator::SemanticNavigator::logwarn |
( |
const std::string & |
msg | ) |
|
void yocs_navigator::SemanticNavigator::nextState |
( |
bool & |
retry, |
|
|
bool & |
final_result, |
|
|
std::string & |
message, |
|
|
const int |
navi_result, |
|
|
const ros::Time |
started_time |
|
) |
| |
|
protected |
void yocs_navigator::SemanticNavigator::processMoveBaseFeedback |
( |
const move_base_msgs::MoveBaseFeedback::ConstPtr & |
feedback, |
|
|
const geometry_msgs::PoseStamped & |
target |
|
) |
| |
|
protected |
void yocs_navigator::SemanticNavigator::processNavigateToGoal |
( |
| ) |
|
|
protected |
void yocs_navigator::SemanticNavigator::processNavigation |
( |
yocs_msgs::NavigateToGoal::ConstPtr |
goal | ) |
|
|
protected |
void yocs_navigator::SemanticNavigator::processPreemptNavigateTo |
( |
| ) |
|
|
protected |
void yocs_navigator::SemanticNavigator::processWaypointList |
( |
const yocs_msgs::WaypointList::ConstPtr & |
msg | ) |
|
|
protected |
void yocs_navigator::SemanticNavigator::spin |
( |
| ) |
|
void yocs_navigator::SemanticNavigator::terminateNavigation |
( |
bool |
success, |
|
|
const std::string |
message |
|
) |
| |
|
protected |
void yocs_navigator::SemanticNavigator::waitForMoveBase |
( |
int & |
move_base_result, |
|
|
const ros::Time & |
start_time, |
|
|
const double |
timeout |
|
) |
| |
|
protected |
double yocs_navigator::SemanticNavigator::distance_to_goal_ |
|
private |
std::string yocs_navigator::SemanticNavigator::global_frame_ |
|
private |
const int yocs_navigator::SemanticNavigator::NAVI_FAILED =17 |
|
staticprivate |
const int yocs_navigator::SemanticNavigator::NAVI_IN_PROGRESS =14 |
|
staticprivate |
const int yocs_navigator::SemanticNavigator::NAVI_RETRY =16 |
|
staticprivate |
const int yocs_navigator::SemanticNavigator::NAVI_SUCCESS =15 |
|
staticprivate |
const int yocs_navigator::SemanticNavigator::NAVI_TIMEOUT =18 |
|
staticprivate |
const int yocs_navigator::SemanticNavigator::NAVI_UNKNOWN =19 |
|
staticprivate |
bool yocs_navigator::SemanticNavigator::navigation_in_progress_ |
|
private |
boost::thread yocs_navigator::SemanticNavigator::order_process_thread_ |
|
private |
std::string yocs_navigator::SemanticNavigator::sub_waypointlist_topic_ |
|
private |
bool yocs_navigator::SemanticNavigator::waypoint_received_ |
|
private |
yocs_msgs::WaypointList yocs_navigator::SemanticNavigator::waypointlist_ |
|
private |
The documentation for this class was generated from the following files: