#include <bank.h>
Public Member Functions | |
BankArgument () | |
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... | |
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.
find_moving_objects::BankArgument::BankArgument | ( | ) |
|
private |
|
private |
|
friend |
|
friend |
|
private |
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.
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
double find_moving_objects::BankArgument::base_confidence |
std::string find_moving_objects::BankArgument::base_frame |
std::string find_moving_objects::BankArgument::delta_position_line_ns |
double find_moving_objects::BankArgument::ema_alpha |
std::string find_moving_objects::BankArgument::fixed_frame |
std::string find_moving_objects::BankArgument::map_frame |
std::string find_moving_objects::BankArgument::node_name_suffix |
int find_moving_objects::BankArgument::nr_scans_in_bank |
double find_moving_objects::BankArgument::object_threshold_bank_tracking_max_delta_distance |
double find_moving_objects::BankArgument::object_threshold_edge_max_delta_range |
int find_moving_objects::BankArgument::object_threshold_max_delta_width_in_points |
double find_moving_objects::BankArgument::object_threshold_max_distance |
double find_moving_objects::BankArgument::object_threshold_min_confidence |
int find_moving_objects::BankArgument::object_threshold_min_nr_points |
double find_moving_objects::BankArgument::object_threshold_min_speed |
std::string find_moving_objects::BankArgument::PC2_message_x_coordinate_field_name |
std::string find_moving_objects::BankArgument::PC2_message_y_coordinate_field_name |
std::string find_moving_objects::BankArgument::PC2_message_z_coordinate_field_name |
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.
double find_moving_objects::BankArgument::PC2_threshold_z_min |
double find_moving_objects::BankArgument::PC2_voxel_leaf_size |
int find_moving_objects::BankArgument::points_per_scan |
int find_moving_objects::BankArgument::publish_buffer_size |
bool find_moving_objects::BankArgument::publish_ema |
bool find_moving_objects::BankArgument::publish_objects |
bool find_moving_objects::BankArgument::publish_objects_closest_point_markers |
bool find_moving_objects::BankArgument::publish_objects_delta_position_lines |
bool find_moving_objects::BankArgument::publish_objects_velocity_arrows |
bool find_moving_objects::BankArgument::publish_objects_width_lines |
|
private |
|
private |
|
private |
|
private |
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
.
|
private |
|
private |
std::string find_moving_objects::BankArgument::topic_ema |
std::string find_moving_objects::BankArgument::topic_objects |
std::string find_moving_objects::BankArgument::topic_objects_closest_point_markers |
std::string find_moving_objects::BankArgument::topic_objects_delta_position_lines |
std::string find_moving_objects::BankArgument::topic_objects_velocity_arrows |
std::string find_moving_objects::BankArgument::topic_objects_width_lines |
std::string find_moving_objects::BankArgument::velocity_arrow_ns |
bool find_moving_objects::BankArgument::velocity_arrows_use_base_frame |
bool find_moving_objects::BankArgument::velocity_arrows_use_fixed_frame |
bool find_moving_objects::BankArgument::velocity_arrows_use_full_gray_scale |
bool find_moving_objects::BankArgument::velocity_arrows_use_sensor_frame |
std::string find_moving_objects::BankArgument::width_line_ns |