#include <scan_unifier_node.h>
Classes | |
struct | config_struct |
This structure holds configuration parameters. More... | |
struct | laser_scan_struct |
This structure holds the variables for one laser-scanner to be unified. More... | |
Public Member Functions | |
void | checkUnifieCondition () |
check in every node-loop if the unifieConditions holds. A unified scan is only published if new laser messages from all scanners have been received | |
bool | get_new_msg_received (int scan_id) |
getter function for new_msg_received variable for checking wether a new msg has been received, triggering publishers accordingly | |
double | getLoopRate () |
getter function for the loop rate | |
void | getParams () |
function to load parameters from ros parameter server | |
void | initLaserScanStructs () |
initialize a vector of laser scan structs (member variable vec_laser_struct_) with a given number (from parameter server, stored in config_ struct) | |
scan_unifier_node () | |
void | set_new_msg_received (bool received, int scan_id) |
setter function for new_msg_received variable | |
void | topicCallbackLaserScan (const sensor_msgs::LaserScan::ConstPtr &scan_in, int scan_id) |
callback function to subscribe to laser scan messages and store them in vec_laser_struct_ | |
sensor_msgs::LaserScan | unifieLaserScans () |
unifie the scan information from all laser scans in vec_laser_struct_ | |
~scan_unifier_node () | |
Public Attributes | |
tf::TransformListener | listener_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | pnh_ |
laser_geometry::LaserProjection | projector_ |
ros::Publisher | topicPub_LaserUnified_ |
Private Attributes | |
config_struct | config_ |
pthread_mutex_t | m_mutex |
std::vector< laser_scan_struct > | vec_laser_struct_ |
Definition at line 85 of file scan_unifier_node.h.
Definition at line 62 of file scan_unifier_node.cpp.
Definition at line 84 of file scan_unifier_node.cpp.
check in every node-loop if the unifieConditions holds. A unified scan is only published if new laser messages from all scanners have been received
checkUnifieCondition input: - output: -
Definition at line 316 of file scan_unifier_node.cpp.
bool scan_unifier_node::get_new_msg_received | ( | int | scan_id | ) |
getter function for new_msg_received variable for checking wether a new msg has been received, triggering publishers accordingly
get_new_msg_received input: - output: -
get_new_msg_received input:
scan | id to find right scan in struct output: - |
Definition at line 166 of file scan_unifier_node.cpp.
double scan_unifier_node::getLoopRate | ( | ) |
getter function for the loop rate
getLoopRate input: - output:
Definition at line 136 of file scan_unifier_node.cpp.
void scan_unifier_node::getParams | ( | ) |
function to load parameters from ros parameter server
getParams input: - output: -
Definition at line 93 of file scan_unifier_node.cpp.
initialize a vector of laser scan structs (member variable vec_laser_struct_) with a given number (from parameter server, stored in config_ struct)
initLaserScanStructs input: - output: -
Definition at line 182 of file scan_unifier_node.cpp.
void scan_unifier_node::set_new_msg_received | ( | bool | received, |
int | scan_id | ||
) |
setter function for new_msg_received variable
set_new_msg_received input:
message | received information output: - |
set_new_msg_received input:
message | received information |
scan | id to find right scan in struct output: - |
Definition at line 150 of file scan_unifier_node.cpp.
void scan_unifier_node::topicCallbackLaserScan | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_in, |
int | scan_id | ||
) |
callback function to subscribe to laser scan messages and store them in vec_laser_struct_
topicCallbackLaserScan input:
a laser scan msg pointer | |
integer to trigger the storage in vec_laser_struct_ output: - |
Definition at line 207 of file scan_unifier_node.cpp.
sensor_msgs::LaserScan scan_unifier_node::unifieLaserScans | ( | ) |
unifie the scan information from all laser scans in vec_laser_struct_
unifieLaserScans input: - output:
a laser scan message containing unified information from all scanners |
Definition at line 230 of file scan_unifier_node.cpp.
config_struct scan_unifier_node::config_ [private] |
Definition at line 126 of file scan_unifier_node.h.
Definition at line 148 of file scan_unifier_node.h.
pthread_mutex_t scan_unifier_node::m_mutex [private] |
Definition at line 124 of file scan_unifier_node.h.
Definition at line 142 of file scan_unifier_node.h.
Definition at line 142 of file scan_unifier_node.h.
Definition at line 151 of file scan_unifier_node.h.
Definition at line 145 of file scan_unifier_node.h.
std::vector<laser_scan_struct> scan_unifier_node::vec_laser_struct_ [private] |
Definition at line 128 of file scan_unifier_node.h.