Commit 2ca0d9e7 authored by dla.adolfsson@gmail.com's avatar dla.adolfsson@gmail.com
Browse files

removed cout

parent af84902b
......@@ -12,9 +12,11 @@
<arg name="robot_prefix" default="robot$(arg robot_id)" />
<include file="$(find graph_map)/launch/VelodyneConvertMotionCompensation.launch" >
<arg name="robot_prefix" value="$(arg robot_prefix)" />
<arg name="input_points_topic" value="$(arg robot_prefix)/velodyne_packets" />
<arg name="output_points_topic" value="$(arg robot_prefix)/velodyne_points_unwarped" />
<arg name="input_points_topic" value="$(arg robot_prefix)/sensors/velodyne_packets" />
<arg name="output_points_topic" value="$(arg robot_prefix)/sensors/velodyne_points_unwarped" />
<arg name="link" default="$(arg robot_prefix)/velodyne_link" />
</include>
......
......@@ -178,6 +178,7 @@ class localisation_node {
initialized=true;
}
void VeloCallback(const velodyne_msgs::VelodyneScan::ConstPtr &msg){
pcl::PointCloud<pcl::PointXYZ> cloud;
......@@ -195,14 +196,13 @@ class localisation_node {
}
pnts.clear();
}
std::cout<<"Velodyne Callback :"<<msg->header.stamp<<", size="<<cloud.size()<<std::endl;
this->processFrame(cloud,t_cloud_end);
}
void PCCallback(const sensor_msgs::PointCloud2::ConstPtr& msg){
pcl::PointCloud<pcl::PointXYZ> pcl_cloud;
pcl::fromROSMsg (*msg, pcl_cloud);
std::cout<<"Callback :"<<msg->header.stamp<<", size="<<pcl_cloud.size()<<std::endl;
this->processFrame(pcl_cloud, msg->header.stamp);
}
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment