Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Friends | Related Functions | List of all members
find_moving_objects::BankArgument Class Reference

#include <bank.h>

Public Member Functions

 BankArgument ()
 

Public Attributes

double angle_max
 
double angle_min
 
double base_confidence
 
std::string base_frame
 
std::string delta_position_line_ns
 
double ema_alpha
 
std::string fixed_frame
 
std::string map_frame
 
std::string node_name_suffix
 
int nr_scans_in_bank
 
double object_threshold_bank_tracking_max_delta_distance
 
double object_threshold_edge_max_delta_range
 
int object_threshold_max_delta_width_in_points
 
double object_threshold_max_distance
 
double object_threshold_min_confidence
 
int object_threshold_min_nr_points
 
double object_threshold_min_speed
 
std::string PC2_message_x_coordinate_field_name
 
std::string PC2_message_y_coordinate_field_name
 
std::string PC2_message_z_coordinate_field_name
 
double PC2_threshold_z_max
 
double PC2_threshold_z_min
 
double PC2_voxel_leaf_size
 
int points_per_scan
 
int publish_buffer_size
 
bool publish_ema
 
bool publish_objects
 
bool publish_objects_closest_point_markers
 
bool publish_objects_delta_position_lines
 
bool publish_objects_velocity_arrows
 
bool publish_objects_width_lines
 
bool sensor_frame_has_z_axis_forward
 
std::string topic_ema
 
std::string topic_objects
 
std::string topic_objects_closest_point_markers
 
std::string topic_objects_delta_position_lines
 
std::string topic_objects_velocity_arrows
 
std::string topic_objects_width_lines
 
std::string velocity_arrow_ns
 
bool velocity_arrows_use_base_frame
 
bool velocity_arrows_use_fixed_frame
 
bool velocity_arrows_use_full_gray_scale
 
bool velocity_arrows_use_sensor_frame
 
std::string width_line_ns
 

Private Member Functions

void check ()
 
void check_PC2 ()
 

Private Attributes

float angle_increment
 
float range_max
 
float range_min
 
float scan_time
 
std::string sensor_frame
 
bool sensor_is_360_degrees
 
float time_increment
 

Friends

std::ostream & operator<< (std::ostream &os, const BankArgument &ba)
 

Related Functions

(Note that these are not member functions.)

class Bank
 Allow Bank to access private members of this class. More...
 

Detailed Description

The member variables of this class define how the bank functions. They are initialized to values that work for quite general cases but, they should be calibrated by the user for the best result. An object of this class is taken as argument in the init() member function of the Bank class.

Definition at line 59 of file bank.h.

Constructor & Destructor Documentation

find_moving_objects::BankArgument::BankArgument ( )

Initializes the member variables to the stated values.

Definition at line 114 of file bank.cpp.

Member Function Documentation

void find_moving_objects::BankArgument::check ( )
private

Validate the specified values. For numeric values, this could include a range check.

Definition at line 282 of file bank.cpp.

void find_moving_objects::BankArgument::check_PC2 ( )
private

Validate the specified sensor_msgs::PointCloud2-specific values. For numeric values, this could include a range check.

Definition at line 386 of file bank.cpp.

Friends And Related Function Documentation

friend class Bank
friend

Allow Bank to access private members of this class.

Definition at line 296 of file bank.h.

std::ostream& operator<< ( std::ostream &  os,
const BankArgument ba 
)
friend

Definition at line 167 of file bank.cpp.

Member Data Documentation

float find_moving_objects::BankArgument::angle_increment
private

The angular difference between two consecutive scan points. For sensor_msgs::LaserScan, the corresponding value of the first message. For sensor_msgs::PointCloud2, this is calculated based on angle_max, angle_min and points_per_scan.

Definition at line 303 of file bank.h.

double find_moving_objects::BankArgument::angle_max

The largest angle (in radians) defined by the scan points in the bank. For sensor_msgs::LaserScan, angle_max is used. For sensor_msgs::PointCloud2, this should be specified (if angle_max-angle_min is smaller than the view angle of the sensor, then the end points in the bank will be the smallest range of all points lying outside the view; if larger, then there will be "empty" ranges in the beginning and end of the bank). Initialized to PI.

Definition at line 86 of file bank.h.

double find_moving_objects::BankArgument::angle_min

The smallest angle (in radians) defined by the scan points in the bank. For sensor_msgs::LaserScan, angle_min is used. For sensor_msgs::PointCloud2, this should be specified (if angle_max-angle_min is smaller than the view angle of the sensor, then the end points in the bank will be the smallest range of all points lying outside the view; if larger, then there will be "empty" ranges in the beginning and end of the bank). Initialized to -PI degrees

Definition at line 77 of file bank.h.

double find_moving_objects::BankArgument::base_confidence

The base confidence of the system/sensor. Initialized to 0.3.

Definition at line 134 of file bank.h.

std::string find_moving_objects::BankArgument::base_frame

The name of the frame fixed on the robot. Initialized to "base_link".

Definition at line 237 of file bank.h.

std::string find_moving_objects::BankArgument::delta_position_line_ns

Namespace of the delta position lines. Initialized to "delta_position_line_ns".

Definition at line 193 of file bank.h.

double find_moving_objects::BankArgument::ema_alpha

General (all apply to LaserScan) The EMA weighting decrease coefficient—a value in [0,1]. Initialized to 1.0 (i.e. no EMA).

Definition at line 63 of file bank.h.

std::string find_moving_objects::BankArgument::fixed_frame

The name of the frame fixed for the robot but movable in the map frame. Initialized to "odom".

Definition at line 233 of file bank.h.

std::string find_moving_objects::BankArgument::map_frame

The name of the map (i.e. the globally fixed) frame. Initialized to "map".

Definition at line 229 of file bank.h.

std::string find_moving_objects::BankArgument::node_name_suffix

Add a suffix to the reported node name in the origin_node_name field of the MovingObjectArray messages. Initialized to the empty string "".

Definition at line 281 of file bank.h.

int find_moving_objects::BankArgument::nr_scans_in_bank

The number of scan messages stored in the bank. Initialized to 11.

Definition at line 67 of file bank.h.

double find_moving_objects::BankArgument::object_threshold_bank_tracking_max_delta_distance

Maximum distance an object is allowed to move in meters between two consecutive scans to continue tracking it through the bank. Initialized to 0.2.

Definition at line 129 of file bank.h.

double find_moving_objects::BankArgument::object_threshold_edge_max_delta_range

The maximum difference in range (meters) between two consecutive scan points belonging to the same object. Initialized to 0.15.

Definition at line 104 of file bank.h.

int find_moving_objects::BankArgument::object_threshold_max_delta_width_in_points

The maximum difference in width (in scan points) an object is allowed to have, between the oldest and newest scans in the bank, in order to report it. Initialized to 5.

Definition at line 120 of file bank.h.

double find_moving_objects::BankArgument::object_threshold_max_distance

The maximum distance in meters from the sensor to the object, in order to report it. Initialized to 6.5.

Definition at line 112 of file bank.h.

double find_moving_objects::BankArgument::object_threshold_min_confidence

The minimum confidence an object must have, in order to report it. Initialized to 0.67.

Definition at line 125 of file bank.h.

int find_moving_objects::BankArgument::object_threshold_min_nr_points

The minimum number of consecutive scan points defining an object. Initialized to 5.

Definition at line 108 of file bank.h.

double find_moving_objects::BankArgument::object_threshold_min_speed

The minimum speed in meters per second an object must have, in order to report it. Initialized to 0.03.

Definition at line 116 of file bank.h.

std::string find_moving_objects::BankArgument::PC2_message_x_coordinate_field_name

The name of the sensor_msgs::PointField specifying the X-coordinate. Initialized to "x".

Definition at line 252 of file bank.h.

std::string find_moving_objects::BankArgument::PC2_message_y_coordinate_field_name

The name of the sensor_msgs::PointField specifying the Y-coordinate. Initialized to "y".

Definition at line 256 of file bank.h.

std::string find_moving_objects::BankArgument::PC2_message_z_coordinate_field_name

The name of the sensor_msgs::PointField specifying the Z-coordinate. Initialized to "z".

Definition at line 260 of file bank.h.

double find_moving_objects::BankArgument::PC2_threshold_z_max

Do not account points with a Z-coordinate larger than this. It is assumed that the Z-axis in the sensor frame is pointing up. If sensor_frame_has_z_axis_forward is set, then the negated Y-coordinate is considered instead of the Z-coordinate of the point, since the Y-axis is pointing down in that case. Initialized to 1.0.

Definition at line 274 of file bank.h.

double find_moving_objects::BankArgument::PC2_threshold_z_min

Do not account points with a Z-coordinate smaller than this. If sensor_frame_has_z_axis_forward is set, then the negated Y-coordinate is considered instead of the Z-coordinate of the point, since the Y-axis is pointing down in that case. Initialized to 0.1.

Definition at line 268 of file bank.h.

double find_moving_objects::BankArgument::PC2_voxel_leaf_size

Approximate distance between two points (in meters) in the cloud. Initialized to 0.02 but, should most likely be calibrated.

Definition at line 264 of file bank.h.

int find_moving_objects::BankArgument::points_per_scan

The number of points per scan message. For sensor_msgs::LaserScan, ranges.size() is used and cannot be changed; for sensor_msgs::PointCloud2, a custom number, defining the resolution of the bank, should be specified. Initialized to 360.

Definition at line 71 of file bank.h.

int find_moving_objects::BankArgument::publish_buffer_size

The size of each publish buffer. Initialized to 10.

Definition at line 225 of file bank.h.

bool find_moving_objects::BankArgument::publish_ema

Whether to publish sensor_msgs::LaserScan messages showing (using intensities) which scan points define objects. Initialized to false.

Definition at line 143 of file bank.h.

bool find_moving_objects::BankArgument::publish_objects

Whether to publish find_moving_objects::MovingObjectArray messages, containing the found objects. Initialized to true.

Definition at line 138 of file bank.h.

bool find_moving_objects::BankArgument::publish_objects_closest_point_markers

Whether to publish the point on each found object closest to the sensor, using sensor_msgs::LaserScan messages. Initialized to false.

Definition at line 148 of file bank.h.

bool find_moving_objects::BankArgument::publish_objects_delta_position_lines

Whether to publish lines, using visualization_msgs::MarkerArray messages, showing the change in position between the oldest and newest scans in the bank for each found object. Initialized to false.

Definition at line 158 of file bank.h.

bool find_moving_objects::BankArgument::publish_objects_velocity_arrows

Whether to publish arrows, using visualization_msgs::MarkerArray messages, showing the position and velocity of each found object. Initialized to false.

Definition at line 153 of file bank.h.

bool find_moving_objects::BankArgument::publish_objects_width_lines

Whether to publish lines, using visualization_msgs::MarkerArray messages, showing the width for each found object. Initialized to false.

Definition at line 163 of file bank.h.

float find_moving_objects::BankArgument::range_max
private

The maximum range the sensor can measure. For sensor_msgs::LaserScan, the corresponding value of the first message. For sensor_msgs::PointCloud2, this is set to object_threshold_max_distance.

Definition at line 325 of file bank.h.

float find_moving_objects::BankArgument::range_min
private

The minimum range the sensor can measure. For sensor_msgs::LaserScan, the corresponding value of the first message. For sensor_msgs::PointCloud2, this is set to 0.01.

Definition at line 320 of file bank.h.

float find_moving_objects::BankArgument::scan_time
private

The time needed for each complete scan. For sensor_msgs::LaserScan, the corresponding value of the first message. For sensor_msgs::PointCloud2, this is set to 0.

Definition at line 315 of file bank.h.

std::string find_moving_objects::BankArgument::sensor_frame
private

The name of the sensor frame. Set to the frame of the sensor.

Definition at line 300 of file bank.h.

bool find_moving_objects::BankArgument::sensor_frame_has_z_axis_forward

Set this to true in case the delivered data is given in a camera/optical frame with the Z-axis pointing forward, instead of the X-axis (and the X-axis pointing right and the Y-axis pointing down). Note that setting this option to true causes the ema and objects_closest_point_markers to be shown incorrectly since they are in fact sensor_msgs::LaserScan messages. The velocity_arrows and delta_position_lines are still shown correctly, though. Initialized to false.

Definition at line 95 of file bank.h.

bool find_moving_objects::BankArgument::sensor_is_360_degrees
private

Whether the sensor is scanning 360 degrees. This is determined based on the angle limits of the bank

Definition at line 330 of file bank.h.

float find_moving_objects::BankArgument::time_increment
private

The time difference between two consecutive scan points. For sensor_msgs::LaserScan, the corresponding value of the first message. For sensor_msgs::PointCloud2, this is set to 0.

Definition at line 309 of file bank.h.

std::string find_moving_objects::BankArgument::topic_ema

The topic on which to publish the messages showing which scan points define objects. Initialized to "/ema;".

Definition at line 205 of file bank.h.

std::string find_moving_objects::BankArgument::topic_objects

The topic on which to publish find_moving_objects::MovingObjectArray messages. Initialized to "/moving_objects_arrays".

Definition at line 201 of file bank.h.

std::string find_moving_objects::BankArgument::topic_objects_closest_point_markers

The topic on which to publish the messages showing the point on each found object closest to the sensor. Initialized to "/objects_closest_point_markers".

Definition at line 209 of file bank.h.

std::string find_moving_objects::BankArgument::topic_objects_delta_position_lines

The topic on which to publish the messages showing the delta position of each found object using lines. Initialized to "/objects_delta_position_lines".

Definition at line 217 of file bank.h.

std::string find_moving_objects::BankArgument::topic_objects_velocity_arrows

The topic on which to publish the messages showing the position and velocity of each found object using arrows. Initialized to "/objects_velocity_arrows".

Definition at line 213 of file bank.h.

std::string find_moving_objects::BankArgument::topic_objects_width_lines

The topic on which to publish the messages showing the width of each found object using lines. Initialized to "/objects_width_lines".

Definition at line 221 of file bank.h.

std::string find_moving_objects::BankArgument::velocity_arrow_ns

Namespace of the velocity arrows. Initialized to "velocity_arrow_ns".

Definition at line 189 of file bank.h.

bool find_moving_objects::BankArgument::velocity_arrows_use_base_frame

Show arrows in base frame (if several frame options are true, then sensor, base, fixed, map (default) is the precedence order). Initialized to false.

Definition at line 179 of file bank.h.

bool find_moving_objects::BankArgument::velocity_arrows_use_fixed_frame

Show arrows in fixed frame (if several frame options are true, then sensor, base, fixed, map (default) is the precedence order). Initialized to false.

Definition at line 184 of file bank.h.

bool find_moving_objects::BankArgument::velocity_arrows_use_full_gray_scale

Whether to color the arrows using the full gray scale ([0,1]; 0=low, 1=high confidence), or to use the grayness [object_threshold_min_confidence,1]. Initialized to false.

Definition at line 168 of file bank.h.

bool find_moving_objects::BankArgument::velocity_arrows_use_sensor_frame

Show arrows in sensor frame (if several frame options are true, then sensor, base, fixed, map (default) is the precedence order). Initialized to false.

Definition at line 174 of file bank.h.

std::string find_moving_objects::BankArgument::width_line_ns

Namespace of the width lines. Initialized to "width_line_ns".

Definition at line 197 of file bank.h.


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


find_moving_objects
Author(s): Andreas Gustavsson
autogenerated on Mon Jun 10 2019 13:13:19