Public Member Functions | |
| void | configure (leg_detector::LegDetectorConfig &config, uint32_t level) |
| double | distance (list< SavedFeature * >::iterator it1, list< SavedFeature * >::iterator it2) |
| void | laserCallback (const sensor_msgs::LaserScan::ConstPtr &scan) |
| LegDetector (ros::NodeHandle nh) | |
| void | pairLegs () |
| void | peopleCallback (const people_msgs::PositionMeasurement::ConstPtr &people_meas) |
| ~LegDetector () | |
Public Attributes | |
| float | connected_thresh_ |
| int | feat_count_ |
| int | feature_id_ |
| CvRTrees | forest |
| tf::MessageFilter < sensor_msgs::LaserScan > | laser_notifier_ |
| message_filters::Subscriber < sensor_msgs::LaserScan > | laser_sub_ |
| ros::Publisher | leg_measurements_pub_ |
| double | leg_reliability_limit_ |
| ros::Publisher | markers_pub_ |
| ScanMask | mask_ |
| int | mask_count_ |
| int | min_points_per_group |
| int | next_p_id_ |
| NodeHandle | nh_ |
| ros::Publisher | people_measurements_pub_ |
| tf::MessageFilter < people_msgs::PositionMeasurement > | people_notifier_ |
| message_filters::Subscriber < people_msgs::PositionMeasurement > | people_sub_ |
| bool | publish_leg_markers_ |
| bool | publish_legs_ |
| bool | publish_people_ |
| bool | publish_people_markers_ |
| char | save_ [100] |
| list< SavedFeature * > | saved_features_ |
| boost::mutex | saved_mutex_ |
| dynamic_reconfigure::Server < leg_detector::LegDetectorConfig > | server_ |
| TransformListener | tfl_ |
| bool | use_seeds_ |
Definition at line 236 of file leg_detector.cpp.
| LegDetector::LegDetector | ( | ros::NodeHandle | nh | ) | [inline] |
Definition at line 277 of file leg_detector.cpp.
| LegDetector::~LegDetector | ( | ) | [inline] |
Definition at line 322 of file leg_detector.cpp.
| void LegDetector::configure | ( | leg_detector::LegDetectorConfig & | config, |
| uint32_t | level | ||
| ) | [inline] |
Definition at line 326 of file leg_detector.cpp.
| double LegDetector::distance | ( | list< SavedFeature * >::iterator | it1, |
| list< SavedFeature * >::iterator | it2 | ||
| ) | [inline] |
Definition at line 354 of file leg_detector.cpp.
| void LegDetector::laserCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan | ) | [inline] |
Definition at line 680 of file leg_detector.cpp.
| void LegDetector::pairLegs | ( | ) | [inline] |
Definition at line 574 of file leg_detector.cpp.
| void LegDetector::peopleCallback | ( | const people_msgs::PositionMeasurement::ConstPtr & | people_meas | ) | [inline] |
Definition at line 363 of file leg_detector.cpp.
Definition at line 249 of file leg_detector.cpp.
Definition at line 251 of file leg_detector.cpp.
Definition at line 258 of file leg_detector.cpp.
| CvRTrees LegDetector::forest |
Definition at line 247 of file leg_detector.cpp.
| tf::MessageFilter<sensor_msgs::LaserScan> LegDetector::laser_notifier_ |
Definition at line 275 of file leg_detector.cpp.
| message_filters::Subscriber<sensor_msgs::LaserScan> LegDetector::laser_sub_ |
Definition at line 273 of file leg_detector.cpp.
Definition at line 267 of file leg_detector.cpp.
Definition at line 263 of file leg_detector.cpp.
Definition at line 268 of file leg_detector.cpp.
Definition at line 243 of file leg_detector.cpp.
Definition at line 245 of file leg_detector.cpp.
Definition at line 264 of file leg_detector.cpp.
Definition at line 262 of file leg_detector.cpp.
Definition at line 239 of file leg_detector.cpp.
Definition at line 266 of file leg_detector.cpp.
| tf::MessageFilter<people_msgs::PositionMeasurement> LegDetector::people_notifier_ |
Definition at line 274 of file leg_detector.cpp.
| message_filters::Subscriber<people_msgs::PositionMeasurement> LegDetector::people_sub_ |
Definition at line 272 of file leg_detector.cpp.
Definition at line 261 of file leg_detector.cpp.
Definition at line 261 of file leg_detector.cpp.
Definition at line 261 of file leg_detector.cpp.
Definition at line 261 of file leg_detector.cpp.
| char LegDetector::save_[100] |
Definition at line 253 of file leg_detector.cpp.
Definition at line 255 of file leg_detector.cpp.
| boost::mutex LegDetector::saved_mutex_ |
Definition at line 256 of file leg_detector.cpp.
| dynamic_reconfigure::Server<leg_detector::LegDetectorConfig> LegDetector::server_ |
Definition at line 270 of file leg_detector.cpp.
Definition at line 241 of file leg_detector.cpp.
Definition at line 260 of file leg_detector.cpp.