#include <ScavTaskColorShirt.h>

Public Member Functions | |
| void | callback_human_detection (const PointCloud::ConstPtr &msg) |
| void | callback_image_saver (const sensor_msgs::ImageConstPtr &msg) |
| void | executeTask (int timeout, TaskResult &result, std::string &record) |
| float | getColorDistance (const pcl::PointXYZRGB *c1, const Rgb *c2) |
| void | motionThread () |
| ScavTaskColorShirt () | |
| ScavTaskColorShirt (ros::NodeHandle *node_handle, std::string path_of_dir, Color shirt_color) | |
| void | stopEarly () |
| void | visionThread () |
Public Attributes | |
| Color | color |
| std::string | directory |
| SearchPlannerSimple * | search_planner_simple |
| bool | task_completed |
Definition at line 31 of file ScavTaskColorShirt.h.
| ScavTaskColorShirt::ScavTaskColorShirt | ( | ros::NodeHandle * | node_handle, |
| std::string | path_of_dir, | ||
| Color | shirt_color | ||
| ) |
Definition at line 104 of file ScavTaskColorShirt.cpp.
| void ScavTaskColorShirt::callback_human_detection | ( | const PointCloud::ConstPtr & | msg | ) |
Definition at line 45 of file ScavTaskColorShirt.cpp.
| void ScavTaskColorShirt::callback_image_saver | ( | const sensor_msgs::ImageConstPtr & | msg | ) |
Definition at line 41 of file ScavTaskColorShirt.cpp.
| void ScavTaskColorShirt::executeTask | ( | int | timeout, |
| TaskResult & | result, | ||
| std::string & | record | ||
| ) | [virtual] |
Implements ScavTask.
Definition at line 158 of file ScavTaskColorShirt.cpp.
| float ScavTaskColorShirt::getColorDistance | ( | const pcl::PointXYZRGB * | c1, |
| const Rgb * | c2 | ||
| ) | [inline] |
Definition at line 54 of file ScavTaskColorShirt.h.
| void ScavTaskColorShirt::motionThread | ( | ) |
Definition at line 126 of file ScavTaskColorShirt.cpp.
| void ScavTaskColorShirt::stopEarly | ( | ) | [virtual] |
Implements ScavTask.
Definition at line 179 of file ScavTaskColorShirt.cpp.
| void ScavTaskColorShirt::visionThread | ( | ) |
Definition at line 142 of file ScavTaskColorShirt.cpp.
Definition at line 46 of file ScavTaskColorShirt.h.
| std::string ScavTaskColorShirt::directory |
Definition at line 47 of file ScavTaskColorShirt.h.
Definition at line 44 of file ScavTaskColorShirt.h.
Definition at line 48 of file ScavTaskColorShirt.h.