Public Member Functions | Public Attributes
PeopleDetectorNode Class Reference

List of all members.

Public Member Functions

void init ()
 read out file with trained hypotheses
 PeopleDetectorNode ()
 Constructor.
void scan_cb (const sensor_msgs::LaserScan::ConstPtr &msg)
 getting range messages from your system and classify them
 ~PeopleDetectorNode ()
 Destructor.

Public Attributes

FILE * f_hypotheses
string hypotheses_filename_
string input_scan_topic_
int list_size_
ros::NodeHandle nh_
int num_hypotheses_
string output_scan_topic_
PeopleDetector pd
ros::Subscriber scan_
sensor_msgs::LaserScan scan_ouput_
ros::Publisher scan_publish_
double threshold_

Detailed Description

Definition at line 66 of file people_detector_node.cpp.


Constructor & Destructor Documentation

Constructor.

Definition at line 88 of file people_detector_node.cpp.

Destructor.

Definition at line 108 of file people_detector_node.cpp.


Member Function Documentation

void PeopleDetectorNode::init ( ) [inline]

read out file with trained hypotheses

Definition at line 116 of file people_detector_node.cpp.

void PeopleDetectorNode::scan_cb ( const sensor_msgs::LaserScan::ConstPtr &  msg) [inline]

getting range messages from your system and classify them

Parameters:
msginput laser scan

Definition at line 138 of file people_detector_node.cpp.


Member Data Documentation

Definition at line 80 of file people_detector_node.cpp.

Definition at line 77 of file people_detector_node.cpp.

Definition at line 76 of file people_detector_node.cpp.

Definition at line 81 of file people_detector_node.cpp.

Definition at line 69 of file people_detector_node.cpp.

Definition at line 78 of file people_detector_node.cpp.

Definition at line 76 of file people_detector_node.cpp.

PeopleDetector PeopleDetectorNode::pd

Definition at line 83 of file people_detector_node.cpp.

Definition at line 73 of file people_detector_node.cpp.

sensor_msgs::LaserScan PeopleDetectorNode::scan_ouput_

Definition at line 71 of file people_detector_node.cpp.

Definition at line 74 of file people_detector_node.cpp.

Definition at line 79 of file people_detector_node.cpp.


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


people_detector_node
Author(s): Oscar Martinez Mozos, Dejan Pangercic(ROS)
autogenerated on Mon Oct 6 2014 08:55:11