#include <bank.h>
Public Member Functions | |
virtual long | addMessage (const sensor_msgs::LaserScan *msg) |
virtual long | addMessage (const sensor_msgs::PointCloud2 *msg, const bool discard_message_if_no_points_added=true) |
Bank (tf2_ros::Buffer *buffer) | |
virtual double | calculateConfidence (const find_moving_objects::MovingObject &mo, const find_moving_objects::BankArgument &ba, const double delta_time, const double mo_old_width) |
void | findAndReportMovingObjects () |
virtual long | init (BankArgument bank_argument, const sensor_msgs::LaserScan *msg) |
virtual long | init (BankArgument bank_argument, const sensor_msgs::PointCloud2 *msg, const bool discard_message_if_no_points_added=true) |
~Bank () | |
Private Types | |
typedef uint8_t | byte_t |
Private Member Functions | |
virtual long | addFirstMessage (const sensor_msgs::LaserScan *) |
virtual long | addFirstMessage (const sensor_msgs::PointCloud2 *, const bool discard_message_if_no_points_added) |
void | advanceIndex () |
void | emaPutMessage () |
int | getOffsetsAndBytes (BankArgument bank_argument, const sensor_msgs::PointCloud2::ConstPtr msg) |
int | getOffsetsAndBytes (BankArgument bank_argument, const sensor_msgs::PointCloud2 *msg) |
void | getOldIndices (const float range_min, const float range_max, const unsigned int object_width_in_points, const int current_level, const unsigned int levels_searched, const unsigned int index_mean, const unsigned int consecutive_failures_to_find_object, const unsigned int threshold_consecutive_failures_to_find_object, int *index_min_old, int *index_mean_old, int *index_max_old, float *range_sum_old, float *range_at_min_index_old, float *range_at_max_index_old) |
std::string | getStringPutPoints () |
void | initBank (BankArgument bank_argument) |
void | initIndex () |
unsigned int | putPoints (const sensor_msgs::PointCloud2::ConstPtr msg) |
unsigned int | putPoints (const sensor_msgs::PointCloud2 *msg) |
void | readPoint (const byte_t *start_of_point, const bool must_reverse_bytes, double *x, double *y, double *z) |
void | resetPutPoints () |
void | reverseBytes (byte_t *bytes, unsigned int nr_bytes) |
The bank contains a number of scan messages and is able to find the position and velocity of moving objects based on these scans.
Note that only ONE single source is supposed to feed the bank with messages and that the "static" parameters (such as the number of scan points and the view angle (cf. FoV) of the sensor etc) must be equal between messages. If they are not, then the behavior of the bank is undefined and the bank might even cause a segmentation fault.
Also note that you might need to sleep for a couple of seconds after creating the Bank
object so that the started tf::tfListener
can collect transformation data.
|
private |
find_moving_objects::Bank::Bank | ( | tf2_ros::Buffer * | buffer | ) |
find_moving_objects::Bank::~Bank | ( | ) |
|
privatevirtual |
|
privatevirtual |
|
virtual |
Add a sensor_msgs::LaserScan
message to the bank (replace the oldest scan message).
msg | Pointer to the received message to be added to the bank. |
sensor_msgs::LaserScan
message to the bank (replace the oldest scan message).msg | Pointer to the received message to be added to the bank. |
|
virtual |
Add a sensor_msgs::PointCloud2
message to the bank (replace the oldest scan message).
msg | Pointer to the received message to be added to the bank. |
sensor_msgs::PointCloud2
message to the bank (replace the oldest scan message).msg | Pointer to the received message to be added to the bank. |
discard_message_if_no_points_added | Discard msg if none of the points in its cloud could be transformed into a point within the field of view specified in bank_argument . |
|
inlineprivate |
|
virtual |
Confidence calculation.
This function must be implemented by the application using the bank.
mo | The object for which to calculate confidence. |
ba | An instance of BankArgument with specified details. |
delta_time | The difference in time between the oldest and newest scans in the bank. |
mo_old_width | The old width of the object. |
Definition at line 87 of file laserscan_interpreter.cpp.
void find_moving_objects::Bank::findAndReportMovingObjects | ( | ) |
|
private |
|
private |
|
private |
|
private |
|
virtual |
Initiate bank with received data, if possible.
This function should be called repeatedly until it succeeds (i.e. returns 0), after this, it should not be called again (doing so would compromise the stored data)!
bank_argument | An instance of BankArgument , specifying the behavior of the bank. |
msg | Pointer to the first received message to be added to the bank. |
This function should be called repeatedly until it succeeds (i.e. returns 0), after this, it should not be called again (doing so would compromise the stored data)!
bank_argument | An instance of BankArgument , specifying the behavior of the bank. |
msg | Pointer to the first received message to be added to the bank. |
|
virtual |
Initiate bank with received data, if possible.
This function should be called repeatedly until it succeeds (i.e. returns 0), after this, it should not be called again (doing so would compromise the stored data)!
bank_argument | An instance of BankArgument , specifying the behavior of the bank. |
msg | Pointer to the first received message to be added to the bank. |
This function should be called repeatedly until it succeeds (i.e. returns 0), after this, it should not be called again (doing so would compromise the stored data)!
bank_argument | An instance of BankArgument , specifying the behavior of the bank. |
msg | Pointer to the first received message to be added to the bank. |
discard_message_if_no_points_added | Discard msg if none of the points in its cloud could be transformed into a point within the field of view specified in bank_argument . |
|
private |
|
inlineprivate |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |