37 #ifndef PEOPLE_TRACKING_FILTER_PEOPLE_TRACKING_NODE_H 38 #define PEOPLE_TRACKING_FILTER_PEOPLE_TRACKING_NODE_H 42 #include <boost/thread/mutex.hpp> 55 #include <sensor_msgs/PointCloud.h> 56 #include <people_msgs/PositionMeasurement.h> 77 void callbackRcv(
const people_msgs::PositionMeasurement::ConstPtr& message);
80 void callbackDrop(
const people_msgs::PositionMeasurement::ConstPtr& message);
116 #endif // PEOPLE_TRACKING_FILTER_PEOPLE_TRACKING_NODE_H
boost::mutex filter_mutex_
void callbackDrop(const people_msgs::PositionMeasurement::ConstPtr &message)
callback for dropped messages
sensor_msgs::PointCloud meas_cloud_
Class representing state with pos and vel.
unsigned int meas_visualize_counter_
tf::TransformListener robot_state_
ros::Publisher people_tracker_vis_pub_
void callbackRcv(const people_msgs::PositionMeasurement::ConstPtr &message)
callback for messages
ros::Publisher people_filter_pub_
std::list< Tracker * > trackers_
trackers
unsigned int tracker_counter_
double reliability_threshold_
virtual ~PeopleTrackingNode()
destructor
double start_distance_min_
message_filters::TimeSequencer< people_msgs::PositionMeasurement > * message_sequencer_
message sequencer
BFL::StatePosVel sys_sigma_
ros::Subscriber people_meas_sub_
PeopleTrackingNode(ros::NodeHandle nh)
constructor
ros::Publisher people_filter_vis_pub_