#include <ScavTaskWhiteBoard.h>

Public Member Functions | |
| void | callback_human_detected (const geometry_msgs::PoseStamped::ConstPtr &msg) |
| void | callback_image (const sensor_msgs::ImageConstPtr &msg) |
| void | executeTask (int timeout, TaskResult &result, std::string &record) |
| bool | inRectangle (Pose p, Pose top_left, Pose top_right, Pose bottom_left) |
| void | motionThread () |
| ScavTaskWhiteBoard () | |
| ScavTaskWhiteBoard (ros::NodeHandle *node_handle, std::string path_of_dir) | |
| void | stopEarly () |
| void | visionThread () |
Public Attributes | |
| std::string | directory |
| SearchPlanner * | search_planner |
| bool | task_completed |
Definition at line 19 of file ScavTaskWhiteBoard.h.
| ScavTaskWhiteBoard::ScavTaskWhiteBoard | ( | ) | [inline] |
Definition at line 22 of file ScavTaskWhiteBoard.h.
| ScavTaskWhiteBoard::ScavTaskWhiteBoard | ( | ros::NodeHandle * | node_handle, |
| std::string | path_of_dir | ||
| ) |
Definition at line 19 of file ScavTaskWhiteBoard.cpp.
| void ScavTaskWhiteBoard::callback_human_detected | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) |
Definition at line 48 of file ScavTaskWhiteBoard.cpp.
| void ScavTaskWhiteBoard::callback_image | ( | const sensor_msgs::ImageConstPtr & | msg | ) |
Definition at line 87 of file ScavTaskWhiteBoard.cpp.
| void ScavTaskWhiteBoard::executeTask | ( | int | timeout, |
| TaskResult & | result, | ||
| std::string & | record | ||
| ) | [virtual] |
Implements ScavTask.
Definition at line 125 of file ScavTaskWhiteBoard.cpp.
| bool ScavTaskWhiteBoard::inRectangle | ( | Pose | p, |
| Pose | top_left, | ||
| Pose | top_right, | ||
| Pose | bottom_left | ||
| ) |
Definition at line 38 of file ScavTaskWhiteBoard.cpp.
| void ScavTaskWhiteBoard::motionThread | ( | ) |
Definition at line 91 of file ScavTaskWhiteBoard.cpp.
| void ScavTaskWhiteBoard::stopEarly | ( | ) | [virtual] |
Implements ScavTask.
Definition at line 144 of file ScavTaskWhiteBoard.cpp.
| void ScavTaskWhiteBoard::visionThread | ( | ) |
Definition at line 110 of file ScavTaskWhiteBoard.cpp.
| std::string ScavTaskWhiteBoard::directory |
Definition at line 34 of file ScavTaskWhiteBoard.h.
Definition at line 33 of file ScavTaskWhiteBoard.h.
Definition at line 36 of file ScavTaskWhiteBoard.h.