Go to the documentation of this file.
53 #include <parameter_pa/parameter_pa_ros.h>
59 int main(
int argc,
char **argv) {
61 ros::init(argc, argv,
"nearfield_map_native_node");
72 cParameterPaRos paramloader;
73 paramloader.load(
"~/degrading_time" , rosparams_.degrading_time_);
74 paramloader.load(
"~/auto_degrading" , rosparams_.auto_degrading_);
75 paramloader.load(
"~/auto_degrading_intervall",
76 rosparams_.auto_degrading_intervall_);
105 const sensor_msgs::PointCloud2ConstPtr &msg) {
107 if (!updateTime(msg->header.stamp)) {
113 if (!
checkTF(msg->header, transform)) {
return;}
124 const sensor_msgs::PointCloud2ConstPtr &msg) {
126 if (!updateTime(msg->header.stamp)) {
132 if (!
checkTF(msg->header, transform)) {
return;}
143 const sensor_msgs::PointCloud2ConstPtr &msg) {
145 if (!updateTime(msg->header.stamp)) {
151 if (!
checkTF(msg->header, transform)) {
return;}
ros::Subscriber sub_laser_full_
subscriber for single laserscans
tf::TransformListener tf_listener_
transformation of different frames
std::string topic_in_laser_scan_
name of the topic for subscribing single laserscans ("in_laser_scan")
ros::Subscriber sub_camera_
subscriber for depth images from camera
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool checkTF(const std_msgs::Header &header, tf::StampedTransform &transform)
void addPcdLaserFullCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for single laserscans
cAddCloudParameter params_addcloud_camera_
parameter for insertion of depth images from camera
void addPcdCameraCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a depth images from camera
int count_camera_
number of inserted depth images from camera (pointclouds)
std::string topic_in_camera_
int main(int argc, char **argv)
~cNearfieldMapDegradingNativeNode()
default destructor
cAddCloudParameter params_addcloud_laser_scan_
parameter for insertion of single laserscans
int count_laser_full_
number of inserted full laserscans (pointclouds)
int count_laser_scan_
number of inserted single laserscans
cAddCloudParameter params_addcloud_laser_full_
parameter for insertion of full laserscans
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
cNearfieldMapDegradingNativeNode()
default constructor
void publish(void)
function for publishing all topics (nearfield map and debugging)
std::string topic_in_laser_full_
name of the topic for subscribing full laserscans ("in_laser_full")
ros::NodeHandle nh_
node handler for topic subscription and advertising
void addPcdLaserScanCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a laserscan
cNearfieldMapPaNodeParameter nodeparams_
parameters
ros::Subscriber sub_laser_scan_
subscriber for a laserscan
nearfield_map
Author(s):
autogenerated on Wed Mar 2 2022 00:42:09