#include <ScavTaskHumanFollowing.h>
Public Member Functions | |
void | amclPoseCallback (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg) |
void | callback_ac_done (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result) |
void | callback_ac_followed (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result) |
void | callback_ac_reached (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result) |
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) |
void | motionThread () |
void | moveToPose (const geometry_msgs::Pose) |
ScavTaskHumanFollowing () | |
ScavTaskHumanFollowing (ros::NodeHandle *node_handle, std::string path_of_dir) | |
void | stopEarly () |
void | visionThread () |
Public Attributes | |
std::string | directory |
SearchPlannerSimple * | search_planner_simple |
bool | task_completed |
Private Attributes | |
MoveBaseClient | ac |
ros::Publisher | cmd_vel_pub |
geometry_msgs::Pose | current_pose |
ros::Time | detected_time |
int | human_detected |
geometry_msgs::PoseStamped | human_following_pose |
geometry_msgs::PoseStamped | human_pose |
ros::Publisher | sound_pub |
Static Private Attributes | |
static const double | human_following_pose_offset = 1 |
static const double | human_pose_delta_threshold = 1.0 |
Definition at line 22 of file ScavTaskHumanFollowing.h.
Definition at line 25 of file ScavTaskHumanFollowing.h.
scav_task_human_following::ScavTaskHumanFollowing::ScavTaskHumanFollowing | ( | ros::NodeHandle * | node_handle, |
std::string | path_of_dir | ||
) |
Definition at line 24 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::amclPoseCallback | ( | const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & | msg | ) |
Definition at line 141 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::callback_ac_done | ( | const actionlib::SimpleClientGoalState & | state, |
const move_base_msgs::MoveBaseResultConstPtr & | result | ||
) |
Definition at line 135 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::callback_ac_followed | ( | const actionlib::SimpleClientGoalState & | state, |
const move_base_msgs::MoveBaseResultConstPtr & | result | ||
) |
Definition at line 113 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::callback_ac_reached | ( | const actionlib::SimpleClientGoalState & | state, |
const move_base_msgs::MoveBaseResultConstPtr & | result | ||
) |
Definition at line 128 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::callback_human_detected | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) |
Definition at line 48 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::callback_image | ( | const sensor_msgs::ImageConstPtr & | msg | ) |
Definition at line 107 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::executeTask | ( | int | timeout, |
TaskResult & | result, | ||
std::string & | record | ||
) | [virtual] |
Implements ScavTask.
Definition at line 250 of file ScavTaskHumanFollowing.cpp.
Definition at line 146 of file ScavTaskHumanFollowing.cpp.
void scav_task_human_following::ScavTaskHumanFollowing::stopEarly | ( | ) | [virtual] |
Implements ScavTask.
Definition at line 262 of file ScavTaskHumanFollowing.cpp.
Definition at line 235 of file ScavTaskHumanFollowing.cpp.
Definition at line 64 of file ScavTaskHumanFollowing.h.
Definition at line 62 of file ScavTaskHumanFollowing.h.
Definition at line 59 of file ScavTaskHumanFollowing.h.
Definition at line 61 of file ScavTaskHumanFollowing.h.
Definition at line 49 of file ScavTaskHumanFollowing.h.
Definition at line 60 of file ScavTaskHumanFollowing.h.
geometry_msgs::PoseStamped scav_task_human_following::ScavTaskHumanFollowing::human_following_pose [private] |
Definition at line 58 of file ScavTaskHumanFollowing.h.
const double scav_task_human_following::ScavTaskHumanFollowing::human_following_pose_offset = 1 [static, private] |
Definition at line 54 of file ScavTaskHumanFollowing.h.
geometry_msgs::PoseStamped scav_task_human_following::ScavTaskHumanFollowing::human_pose [private] |
Definition at line 57 of file ScavTaskHumanFollowing.h.
const double scav_task_human_following::ScavTaskHumanFollowing::human_pose_delta_threshold = 1.0 [static, private] |
Definition at line 55 of file ScavTaskHumanFollowing.h.
Definition at line 48 of file ScavTaskHumanFollowing.h.
Definition at line 63 of file ScavTaskHumanFollowing.h.
Definition at line 51 of file ScavTaskHumanFollowing.h.