|
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.
Definition at line 356 of file bank.h.
long find_moving_objects::Bank::init |
( |
BankArgument |
bank_argument, |
|
|
const sensor_msgs::LaserScan * |
msg |
|
) |
| |
|
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)!
- Parameters
-
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. |
- Returns
- 0 on success, -1 if this function must be called again. 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)!
- Parameters
-
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. |
- Returns
- 0 on success, -1 if this function must be called again.
Definition at line 2740 of file bank.cpp.
long find_moving_objects::Bank::init |
( |
BankArgument |
bank_argument, |
|
|
const sensor_msgs::PointCloud2 * |
msg, |
|
|
const bool |
discard_message_if_no_points_added = true |
|
) |
| |
|
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)!
- Parameters
-
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. |
- Returns
- 0 on success, -1 if this function must be called again. 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)!
- Parameters
-
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 . |
- Returns
- 0 on success, -1 if this function must be called again.
Definition at line 2872 of file bank.cpp.