Skip to content

Commit

Permalink
Rename variables.
Browse files Browse the repository at this point in the history
  • Loading branch information
yukikitsukawa committed Nov 4, 2016
1 parent cf0a919 commit eb81f4c
Show file tree
Hide file tree
Showing 9 changed files with 98 additions and 98 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(points_filter)
project(points_downsampler)

find_package(catkin REQUIRED COMPONENTS
roscpp
Expand All @@ -13,7 +13,7 @@ find_package(catkin REQUIRED COMPONENTS

add_message_files(
FILES
PointsFilterInfo.msg
PointsDownsamplerInfo.msg
)

generate_messages(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="node_name" default="voxel_grid_filter" />
<arg name="output_log" default="false" />

<node pkg="points_filter" name="$(arg node_name)" type="$(arg node_name)">
<node pkg="points_downsampler" name="$(arg node_name)" type="$(arg node_name)">
<remap from="/points_raw" to="/sync_drivers/points_raw" if="$(arg sync)" />
<param name="output_log" value="$(arg output_log)" />
</node>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,16 +37,16 @@

#include <runtime_manager/ConfigDistanceFilter.h>

#include <points_filter/PointsFilterInfo.h>
#include <points_downsampler/PointsDownsamplerInfo.h>

#include <chrono>

ros::Publisher filtered_points_pub;

static int sample_num = 1000;

static ros::Publisher points_filter_info_pub;
static points_filter::PointsFilterInfo points_filter_info_msg;
static ros::Publisher points_downsampler_info_pub;
static points_downsampler::PointsDownsamplerInfo points_downsampler_info_msg;

static std::chrono::time_point<std::chrono::system_clock> filter_start, filter_end;

Expand Down Expand Up @@ -106,29 +106,29 @@ static void scan_callback(const sensor_msgs::PointCloud2::ConstPtr& input)
filtered_msg.header = input->header;
filtered_points_pub.publish(filtered_msg);

points_filter_info_msg.header = input->header;
points_filter_info_msg.filter_name = "distance_filter";
points_filter_info_msg.original_points_size = points_num;
points_filter_info_msg.filtered_points_size = filtered_scan_ptr->size();
points_filter_info_msg.original_ring_size = 0;
points_filter_info_msg.original_ring_size = 0;
points_filter_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_filter_info_pub.publish(points_filter_info_msg);
points_downsampler_info_msg.header = input->header;
points_downsampler_info_msg.filter_name = "distance_filter";
points_downsampler_info_msg.original_points_size = points_num;
points_downsampler_info_msg.filtered_points_size = filtered_scan_ptr->size();
points_downsampler_info_msg.original_ring_size = 0;
points_downsampler_info_msg.original_ring_size = 0;
points_downsampler_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_downsampler_info_pub.publish(points_downsampler_info_msg);

if(_output_log == true){
if(!ofs){
std::cerr << "Could not open " << filename << "." << std::endl;
exit(1);
}
ofs << points_filter_info_msg.header.seq << ","
<< points_filter_info_msg.header.stamp << ","
<< points_filter_info_msg.header.frame_id << ","
<< points_filter_info_msg.filter_name << ","
<< points_filter_info_msg.original_points_size << ","
<< points_filter_info_msg.filtered_points_size << ","
<< points_filter_info_msg.original_ring_size << ","
<< points_filter_info_msg.filtered_ring_size << ","
<< points_filter_info_msg.exe_time << ","
ofs << points_downsampler_info_msg.header.seq << ","
<< points_downsampler_info_msg.header.stamp << ","
<< points_downsampler_info_msg.header.frame_id << ","
<< points_downsampler_info_msg.filter_name << ","
<< points_downsampler_info_msg.original_points_size << ","
<< points_downsampler_info_msg.filtered_points_size << ","
<< points_downsampler_info_msg.original_ring_size << ","
<< points_downsampler_info_msg.filtered_ring_size << ","
<< points_downsampler_info_msg.exe_time << ","
<< std::endl;
}

Expand All @@ -153,7 +153,7 @@ int main(int argc, char** argv)

// Publishers
filtered_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/filtered_points", 10);
points_filter_info_pub = nh.advertise<points_filter::PointsFilterInfo>("/points_filter_info", 1000);
points_downsampler_info_pub = nh.advertise<points_downsampler::PointsDownsamplerInfo>("/points_downsampler_info", 1000);

// Subscribers
ros::Subscriber config_sub = nh.subscribe("config/distance_filter", 10, config_callback);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,16 +36,16 @@

#include <runtime_manager/ConfigRandomFilter.h>

#include <points_filter/PointsFilterInfo.h>
#include <points_downsampler/PointsDownsamplerInfo.h>

#include <chrono>

ros::Publisher filtered_points_pub;

static int sample_num = 1000;

static ros::Publisher points_filter_info_pub;
static points_filter::PointsFilterInfo points_filter_info_msg;
static ros::Publisher points_downsampler_info_pub;
static points_downsampler::PointsDownsamplerInfo points_downsampler_info_msg;

static std::chrono::time_point<std::chrono::system_clock> filter_start, filter_end;

Expand Down Expand Up @@ -75,7 +75,7 @@ static void scan_callback(const sensor_msgs::PointCloud2::ConstPtr& input)

for (int i = 0; i < points_num; i++)
{
if (filtered_scan_ptr->size() < sample_num && i % step == 0)
if ((int)filtered_scan_ptr->size() < sample_num && i % step == 0)
{
filtered_scan_ptr->points.push_back(scan.at(i));
}
Expand All @@ -89,29 +89,29 @@ static void scan_callback(const sensor_msgs::PointCloud2::ConstPtr& input)
filtered_msg.header = input->header;
filtered_points_pub.publish(filtered_msg);

points_filter_info_msg.header = input->header;
points_filter_info_msg.filter_name = "random_filter";
points_filter_info_msg.original_points_size = points_num;
points_filter_info_msg.filtered_points_size = filtered_scan_ptr->size();
points_filter_info_msg.original_ring_size = 0;
points_filter_info_msg.filtered_ring_size = 0;
points_filter_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_filter_info_pub.publish(points_filter_info_msg);
points_downsampler_info_msg.header = input->header;
points_downsampler_info_msg.filter_name = "random_filter";
points_downsampler_info_msg.original_points_size = points_num;
points_downsampler_info_msg.filtered_points_size = filtered_scan_ptr->size();
points_downsampler_info_msg.original_ring_size = 0;
points_downsampler_info_msg.filtered_ring_size = 0;
points_downsampler_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_downsampler_info_pub.publish(points_downsampler_info_msg);

if(_output_log == true){
if(!ofs){
std::cerr << "Could not open " << filename << "." << std::endl;
exit(1);
}
ofs << points_filter_info_msg.header.seq << ","
<< points_filter_info_msg.header.stamp << ","
<< points_filter_info_msg.header.frame_id << ","
<< points_filter_info_msg.filter_name << ","
<< points_filter_info_msg.original_points_size << ","
<< points_filter_info_msg.filtered_points_size << ","
<< points_filter_info_msg.original_ring_size << ","
<< points_filter_info_msg.filtered_ring_size << ","
<< points_filter_info_msg.exe_time << ","
ofs << points_downsampler_info_msg.header.seq << ","
<< points_downsampler_info_msg.header.stamp << ","
<< points_downsampler_info_msg.header.frame_id << ","
<< points_downsampler_info_msg.filter_name << ","
<< points_downsampler_info_msg.original_points_size << ","
<< points_downsampler_info_msg.filtered_points_size << ","
<< points_downsampler_info_msg.original_ring_size << ","
<< points_downsampler_info_msg.filtered_ring_size << ","
<< points_downsampler_info_msg.exe_time << ","
<< std::endl;
}

Expand All @@ -136,7 +136,7 @@ int main(int argc, char** argv)

// Publishers
filtered_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/filtered_points", 10);
points_filter_info_pub = nh.advertise<points_filter::PointsFilterInfo>("/points_filter_info", 1000);
points_downsampler_info_pub = nh.advertise<points_downsampler::PointsDownsamplerInfo>("/points_downsampler_info", 1000);

// Subscribers
ros::Subscriber config_sub = nh.subscribe("config/random_filter", 10, config_callback);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#include <runtime_manager/ConfigRingFilter.h>

#include <points_filter/PointsFilterInfo.h>
#include <points_downsampler/PointsDownsamplerInfo.h>

#include <chrono>

Expand All @@ -51,8 +51,8 @@ static double voxel_leaf_size = 2.0;
int ring_max = 0;
int ring_div = 3;

static ros::Publisher points_filter_info_pub;
static points_filter::PointsFilterInfo points_filter_info_msg;
static ros::Publisher points_downsampler_info_pub;
static points_downsampler::PointsDownsamplerInfo points_downsampler_info_msg;

static std::chrono::time_point<std::chrono::system_clock> filter_start, filter_end;

Expand Down Expand Up @@ -120,36 +120,36 @@ static void scan_callback(const sensor_msgs::PointCloud2::ConstPtr& input)
filtered_msg.header = input->header;
filtered_points_pub.publish(filtered_msg);

points_filter_info_msg.header = input->header;
points_filter_info_msg.filter_name = "ring_filter";
points_filter_info_msg.original_points_size = scan.size();
points_downsampler_info_msg.header = input->header;
points_downsampler_info_msg.filter_name = "ring_filter";
points_downsampler_info_msg.original_points_size = scan.size();
if (voxel_leaf_size >= 0.1)
{
points_filter_info_msg.filtered_points_size = filtered_scan_ptr->size();
points_downsampler_info_msg.filtered_points_size = filtered_scan_ptr->size();
}
else
{
points_filter_info_msg.filtered_points_size = scan_ptr->size();
points_downsampler_info_msg.filtered_points_size = scan_ptr->size();
}
points_filter_info_msg.original_ring_size = ring_max;
points_filter_info_msg.filtered_ring_size = ring_max / ring_div;
points_filter_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_filter_info_pub.publish(points_filter_info_msg);
points_downsampler_info_msg.original_ring_size = ring_max;
points_downsampler_info_msg.filtered_ring_size = ring_max / ring_div;
points_downsampler_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_downsampler_info_pub.publish(points_downsampler_info_msg);

if(_output_log == true){
if(!ofs){
std::cerr << "Could not open " << filename << "." << std::endl;
exit(1);
}
ofs << points_filter_info_msg.header.seq << ","
<< points_filter_info_msg.header.stamp << ","
<< points_filter_info_msg.header.frame_id << ","
<< points_filter_info_msg.filter_name << ","
<< points_filter_info_msg.original_points_size << ","
<< points_filter_info_msg.filtered_points_size << ","
<< points_filter_info_msg.original_ring_size << ","
<< points_filter_info_msg.filtered_ring_size << ","
<< points_filter_info_msg.exe_time << ","
ofs << points_downsampler_info_msg.header.seq << ","
<< points_downsampler_info_msg.header.stamp << ","
<< points_downsampler_info_msg.header.frame_id << ","
<< points_downsampler_info_msg.filter_name << ","
<< points_downsampler_info_msg.original_points_size << ","
<< points_downsampler_info_msg.filtered_points_size << ","
<< points_downsampler_info_msg.original_ring_size << ","
<< points_downsampler_info_msg.filtered_ring_size << ","
<< points_downsampler_info_msg.exe_time << ","
<< std::endl;
}

Expand All @@ -174,7 +174,7 @@ int main(int argc, char** argv)

// Publishers
filtered_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/filtered_points", 10);
points_filter_info_pub = nh.advertise<points_filter::PointsFilterInfo>("/points_filter_info", 1000);
points_downsampler_info_pub = nh.advertise<points_downsampler::PointsDownsamplerInfo>("/points_downsampler_info", 1000);

// Subscribers
ros::Subscriber config_sub = nh.subscribe("config/ring_filter", 10, config_callback);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@

#include <runtime_manager/ConfigVoxelGridFilter.h>

#include <points_filter/PointsFilterInfo.h>
#include <points_downsampler/PointsDownsamplerInfo.h>

#include <chrono>

Expand All @@ -46,8 +46,8 @@ ros::Publisher filtered_points_pub;
// Leaf size of VoxelGrid filter.
static double voxel_leaf_size = 2.0;

static ros::Publisher points_filter_info_pub;
static points_filter::PointsFilterInfo points_filter_info_msg;
static ros::Publisher points_downsampler_info_pub;
static points_downsampler::PointsDownsamplerInfo points_downsampler_info_msg;

static std::chrono::time_point<std::chrono::system_clock> filter_start, filter_end;

Expand Down Expand Up @@ -92,36 +92,36 @@ static void scan_callback(const sensor_msgs::PointCloud2::ConstPtr& input)
filtered_msg.header = input->header;
filtered_points_pub.publish(filtered_msg);

points_filter_info_msg.header = input->header;
points_filter_info_msg.filter_name = "voxel_grid_filter";
points_filter_info_msg.original_points_size = scan.size();
points_downsampler_info_msg.header = input->header;
points_downsampler_info_msg.filter_name = "voxel_grid_filter";
points_downsampler_info_msg.original_points_size = scan.size();
if (voxel_leaf_size >= 0.1)
{
points_filter_info_msg.filtered_points_size = filtered_scan_ptr->size();
points_downsampler_info_msg.filtered_points_size = filtered_scan_ptr->size();
}
else
{
points_filter_info_msg.filtered_points_size = scan_ptr->size();
points_downsampler_info_msg.filtered_points_size = scan_ptr->size();
}
points_filter_info_msg.original_ring_size = 0;
points_filter_info_msg.filtered_ring_size = 0;
points_filter_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_filter_info_pub.publish(points_filter_info_msg);
points_downsampler_info_msg.original_ring_size = 0;
points_downsampler_info_msg.filtered_ring_size = 0;
points_downsampler_info_msg.exe_time = std::chrono::duration_cast<std::chrono::microseconds>(filter_end - filter_start).count() / 1000.0;
points_downsampler_info_pub.publish(points_downsampler_info_msg);

if(_output_log == true){
if(!ofs){
std::cerr << "Could not open " << filename << "." << std::endl;
exit(1);
}
ofs << points_filter_info_msg.header.seq << ","
<< points_filter_info_msg.header.stamp << ","
<< points_filter_info_msg.header.frame_id << ","
<< points_filter_info_msg.filter_name << ","
<< points_filter_info_msg.original_points_size << ","
<< points_filter_info_msg.filtered_points_size << ","
<< points_filter_info_msg.original_ring_size << ","
<< points_filter_info_msg.filtered_ring_size << ","
<< points_filter_info_msg.exe_time << ","
ofs << points_downsampler_info_msg.header.seq << ","
<< points_downsampler_info_msg.header.stamp << ","
<< points_downsampler_info_msg.header.frame_id << ","
<< points_downsampler_info_msg.filter_name << ","
<< points_downsampler_info_msg.original_points_size << ","
<< points_downsampler_info_msg.filtered_points_size << ","
<< points_downsampler_info_msg.original_ring_size << ","
<< points_downsampler_info_msg.filtered_ring_size << ","
<< points_downsampler_info_msg.exe_time << ","
<< std::endl;
}

Expand All @@ -146,7 +146,7 @@ int main(int argc, char** argv)

// Publishers
filtered_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/filtered_points", 10);
points_filter_info_pub = nh.advertise<points_filter::PointsFilterInfo>("/points_filter_info", 1000);
points_downsampler_info_pub = nh.advertise<points_downsampler::PointsDownsamplerInfo>("/points_downsampler_info", 1000);

// Subscribers
ros::Subscriber config_sub = nh.subscribe("config/voxel_grid_filter", 10, config_callback);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<package>
<name>points_filter</name>
<name>points_downsampler</name>
<version>0.0.0</version>
<description>The points_filter package</description>
<description>The points_downsampler package</description>
<maintainer email="yuki@ertl.jp">Yuki KITSUKAWA</maintainer>
<license>BSD</license>

Expand Down
Loading

0 comments on commit eb81f4c

Please sign in to comment.