Public Member Functions | Public Attributes | List of all members
LegDetector Class Reference

Public Member Functions

void configure (leg_detector::LegDetectorConfig &config, uint32_t level)
 
double distance (std::list< SavedFeature * >::iterator it1, std::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_
 
cv::Ptr< cv::ml::RTrees > 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_
 
laser_processor::ScanMask mask_
 
int mask_count_
 
int min_points_per_group
 
int next_p_id_
 
ros::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]
 
std::list< SavedFeature * > saved_features_
 
boost::mutex saved_mutex_
 
dynamic_reconfigure::Server< leg_detector::LegDetectorConfig > server_
 
tf::TransformListener tfl_
 
bool use_seeds_
 

Detailed Description

Definition at line 231 of file leg_detector.cpp.

Constructor & Destructor Documentation

LegDetector::LegDetector ( ros::NodeHandle  nh)
inlineexplicit

Definition at line 273 of file leg_detector.cpp.

LegDetector::~LegDetector ( )
inline

Definition at line 320 of file leg_detector.cpp.

Member Function Documentation

void LegDetector::configure ( leg_detector::LegDetectorConfig &  config,
uint32_t  level 
)
inline

Definition at line 324 of file leg_detector.cpp.

double LegDetector::distance ( std::list< SavedFeature * >::iterator  it1,
std::list< SavedFeature * >::iterator  it2 
)
inline

Definition at line 352 of file leg_detector.cpp.

void LegDetector::laserCallback ( const sensor_msgs::LaserScan::ConstPtr &  scan)
inline

Definition at line 686 of file leg_detector.cpp.

void LegDetector::pairLegs ( )
inline

Definition at line 581 of file leg_detector.cpp.

void LegDetector::peopleCallback ( const people_msgs::PositionMeasurement::ConstPtr &  people_meas)
inline

Definition at line 362 of file leg_detector.cpp.

Member Data Documentation

float LegDetector::connected_thresh_

Definition at line 245 of file leg_detector.cpp.

int LegDetector::feat_count_

Definition at line 247 of file leg_detector.cpp.

int LegDetector::feature_id_

Definition at line 254 of file leg_detector.cpp.

cv::Ptr<cv::ml::RTrees> LegDetector::forest

Definition at line 243 of file leg_detector.cpp.

tf::MessageFilter<sensor_msgs::LaserScan> LegDetector::laser_notifier_

Definition at line 271 of file leg_detector.cpp.

message_filters::Subscriber<sensor_msgs::LaserScan> LegDetector::laser_sub_

Definition at line 269 of file leg_detector.cpp.

ros::Publisher LegDetector::leg_measurements_pub_

Definition at line 263 of file leg_detector.cpp.

double LegDetector::leg_reliability_limit_

Definition at line 259 of file leg_detector.cpp.

ros::Publisher LegDetector::markers_pub_

Definition at line 264 of file leg_detector.cpp.

laser_processor::ScanMask LegDetector::mask_

Definition at line 238 of file leg_detector.cpp.

int LegDetector::mask_count_

Definition at line 240 of file leg_detector.cpp.

int LegDetector::min_points_per_group

Definition at line 260 of file leg_detector.cpp.

int LegDetector::next_p_id_

Definition at line 258 of file leg_detector.cpp.

ros::NodeHandle LegDetector::nh_

Definition at line 234 of file leg_detector.cpp.

ros::Publisher LegDetector::people_measurements_pub_

Definition at line 262 of file leg_detector.cpp.

tf::MessageFilter<people_msgs::PositionMeasurement> LegDetector::people_notifier_

Definition at line 270 of file leg_detector.cpp.

message_filters::Subscriber<people_msgs::PositionMeasurement> LegDetector::people_sub_

Definition at line 268 of file leg_detector.cpp.

bool LegDetector::publish_leg_markers_

Definition at line 257 of file leg_detector.cpp.

bool LegDetector::publish_legs_

Definition at line 257 of file leg_detector.cpp.

bool LegDetector::publish_people_

Definition at line 257 of file leg_detector.cpp.

bool LegDetector::publish_people_markers_

Definition at line 257 of file leg_detector.cpp.

char LegDetector::save_[100]

Definition at line 249 of file leg_detector.cpp.

std::list<SavedFeature*> LegDetector::saved_features_

Definition at line 251 of file leg_detector.cpp.

boost::mutex LegDetector::saved_mutex_

Definition at line 252 of file leg_detector.cpp.

dynamic_reconfigure::Server<leg_detector::LegDetectorConfig> LegDetector::server_

Definition at line 266 of file leg_detector.cpp.

tf::TransformListener LegDetector::tfl_

Definition at line 236 of file leg_detector.cpp.

bool LegDetector::use_seeds_

Definition at line 256 of file leg_detector.cpp.


The documentation for this class was generated from the following file:


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:50