#include <ar_human_proc.h>
Public Member Functions | |
| void | ar_pose_callback (const ar_pose::ARMarkers::ConstPtr &) |
| ar_pose_reader (std_msgs::String topic_name, ros::NodeHandle *n) | |
| social_filter::humanPose | getPose () |
| void | init () |
Public Attributes | |
| ros::Subscriber | ar_pose_sub |
| tf::TransformListener | listener |
| ros::NodeHandle * | local_n |
| std_msgs::String | name |
| int | num_markers |
| geometry_msgs::PoseStamped | source_pose |
| geometry_msgs::PoseStamped | target_pose |
Definition at line 69 of file ar_human_proc.h.
| ar_pose_reader::ar_pose_reader | ( | std_msgs::String | topic_name, |
| ros::NodeHandle * | n | ||
| ) |
Definition at line 38 of file ar_human_proc.cpp.
| void ar_pose_reader::ar_pose_callback | ( | const ar_pose::ARMarkers::ConstPtr & | markers | ) |
publish trajectories
Definition at line 63 of file ar_human_proc.cpp.
| social_filter::humanPose ar_pose_reader::getPose | ( | ) |
| void ar_pose_reader::init | ( | ) |
Definition at line 44 of file ar_human_proc.cpp.
| ros::Subscriber ar_pose_reader::ar_pose_sub |
Definition at line 78 of file ar_human_proc.h.
| tf::TransformListener ar_pose_reader::listener |
Definition at line 83 of file ar_human_proc.h.
| ros::NodeHandle* ar_pose_reader::local_n |
Definition at line 77 of file ar_human_proc.h.
| std_msgs::String ar_pose_reader::name |
Definition at line 80 of file ar_human_proc.h.
| int ar_pose_reader::num_markers |
Definition at line 81 of file ar_human_proc.h.
| geometry_msgs::PoseStamped ar_pose_reader::source_pose |
Definition at line 84 of file ar_human_proc.h.
| geometry_msgs::PoseStamped ar_pose_reader::target_pose |
Definition at line 85 of file ar_human_proc.h.