35 int main(
int argc,
char **argv)
38 ros::init(argc, argv,
"listener");
42 string pointcloud_input;
43 string pointcloud_output;
45 double min_x, max_x, min_y, max_y;
51 ros::NodeHandle private_node_handle_(
"~");
52 private_node_handle_.param(
"pointcloud_input", pointcloud_input,
string(
"pointcloud_input"));
53 private_node_handle_.param(
"pointcloud_output", pointcloud_output,
string(
"pointcloud_output"));
54 private_node_handle_.param(
"frame_id", filt->
frame_id,
string(
"frame_id"));
57 private_node_handle_.param(
"min_x", min_x,
double(min_x));
58 private_node_handle_.param(
"max_x", max_x,
double(max_x));
59 private_node_handle_.param(
"min_y", min_y,
double(min_y));
60 private_node_handle_.param(
"max_y", max_y,
double(max_y));
61 private_node_handle_.param(
"min_z", filt->
min_z,
double(filt->
min_z));
62 private_node_handle_.param(
"max_z", filt->
max_z,
double(filt->
max_z));
65 PointXYZRGB point; point.z=0.0;
66 point.x=min_x; point.y=max_y;
68 point.x=max_x; point.y=max_y;
70 point.x=max_x; point.y=min_y;
72 point.x=min_x; point.y=min_y;
81 ros::Publisher pub_message = n.advertise<sensor_msgs::PointCloud2>(pointcloud_output.c_str(), 10);
87 tf::TransformListener listener_center_bumper;
double min_z
Minimum value for Z pointcloud.
double max_z
Maximum value for Z pointcloud.
string frame_id
The frame_id to transform.
int main(int argc, char **argv)
tf::TransformListener * transform_listener_ptr
Pointer to a transform listener.
ros::Publisher * pub_ptr
Pointer to pointcloud publisher.
double voxel_size
Voxel grid size.
filtering class declaration
PointCloud< T > convex_hull
The convex hull for cloud extraction.