#include <SearchPlanner.h>

Public Member Functions | |
| void | analyzeScene (float angle, float angular_vel) |
| geometry_msgs::PoseWithCovarianceStamped | getCurrPosition () |
| bool | getTargetDetection () |
| void | moveToNextScene (const geometry_msgs::PoseStamped &next_goal) |
| SearchPlanner () | |
| SearchPlanner (ros::NodeHandle *nh, std::string path_to_yaml, float goal_tolerance) | |
| geometry_msgs::PoseStamped | selectNextScene (const std::vector< float > &b, int &next_goal_index) |
| void | setTargetDetection (bool detected) |
| void | updateBelief (int) |
Public Attributes | |
| std::vector< float > | belief |
| ros::ServiceClient | client_make_plan |
| geometry_msgs::PoseStamped | next_goal |
| std::vector < geometry_msgs::PoseStamped > | positions |
| ros::Publisher | pub_simple_goal |
| ros::Subscriber | sub_amcl_pose |
| bool | targetDetected |
| float | tolerance |
Definition at line 47 of file SearchPlanner.h.
| SearchPlanner::SearchPlanner | ( | ) | [inline] |
Definition at line 50 of file SearchPlanner.h.
| SearchPlanner::SearchPlanner | ( | ros::NodeHandle * | nh, |
| std::string | path_to_yaml, | ||
| float | goal_tolerance | ||
| ) |
Definition at line 98 of file SearchPlanner.cpp.
| void SearchPlanner::analyzeScene | ( | float | angle, |
| float | angular_vel | ||
| ) |
Definition at line 220 of file SearchPlanner.cpp.
| geometry_msgs::PoseWithCovarianceStamped SearchPlanner::getCurrPosition | ( | ) |
| bool SearchPlanner::getTargetDetection | ( | ) | [inline] |
Definition at line 70 of file SearchPlanner.h.
| void SearchPlanner::moveToNextScene | ( | const geometry_msgs::PoseStamped & | next_goal | ) |
Definition at line 194 of file SearchPlanner.cpp.
| geometry_msgs::PoseStamped SearchPlanner::selectNextScene | ( | const std::vector< float > & | b, |
| int & | next_goal_index | ||
| ) |
Definition at line 149 of file SearchPlanner.cpp.
| void SearchPlanner::setTargetDetection | ( | bool | detected | ) | [inline] |
Definition at line 67 of file SearchPlanner.h.
| void SearchPlanner::updateBelief | ( | int | next_goal_index | ) |
Definition at line 248 of file SearchPlanner.cpp.
| std::vector<float> SearchPlanner::belief |
Definition at line 54 of file SearchPlanner.h.
Definition at line 56 of file SearchPlanner.h.
| geometry_msgs::PoseStamped SearchPlanner::next_goal |
Definition at line 62 of file SearchPlanner.h.
| std::vector<geometry_msgs::PoseStamped> SearchPlanner::positions |
Definition at line 53 of file SearchPlanner.h.
Definition at line 57 of file SearchPlanner.h.
Definition at line 58 of file SearchPlanner.h.
Definition at line 64 of file SearchPlanner.h.
| float SearchPlanner::tolerance |
Definition at line 65 of file SearchPlanner.h.