ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I could solve the problem by changing my prespective a little bit. So instead of moving the pointClouds, we can creat a Marker which is consisted of many points which have the same color as the points of the pointcloud and then we can move or rotate the frame of the marker. Here's a code for making the marker ( If anyone has any other recommendation I would be very happy to hear that!!):
#include<ros/ros.h>
#include<visualization_msgs/Marker.h>
#include<pcl-1.8/pcl/point_cloud.h>
#include<pcl_conversions/pcl_conversions.h>
#include<pcl-1.8/pcl/point_types.h>
#include <sensor_msgs/PointCloud.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_cloud_conversion.h>
#include<pcl-1.8/pcl/filters/passthrough.h>
ros::Publisher pub;
ros::Publisher pass_pub;
void cloud_cb(const pcl::PCLPointCloud2ConstPtr &input)
{
// Getting the target point cloud
pcl::PassThrough<pcl::PCLPointCloud2> pass;
pcl::PCLPointCloud2::Ptr flt_input(new pcl::PCLPointCloud2);
pass.setInputCloud(input);
pass.setFilterFieldName("x");
pass.setFilterLimits(0,2);
pass.filter(*flt_input);
pass.setInputCloud(flt_input);
pass.setFilterFieldName("y");
pass.setFilterLimits(-2,0);
pass.filter(*flt_input);
pass.setInputCloud(flt_input);
pass.setFilterFieldName("z");
pass.setFilterLimits(0,2);
pass.filter(*flt_input);
pass_pub.publish(*flt_input);
// Converting PointCloud2 to PointXYZRGBA
pcl::PointCloud<pcl::PointXYZRGBA> input_xyz;
pcl::fromPCLPointCloud2(*flt_input,input_xyz);
//create the marker
visualization_msgs::Marker marker;
marker.header.frame_id="/camera1";
marker.header.stamp=ros::Time::now();
marker.ns = "pcl_marker";
marker.id = 1;
marker.type = visualization_msgs::Marker::POINTS;
marker.action = visualization_msgs::Marker::ADD;
marker.lifetime = ros::Duration();
marker.scale.x = 0.004;
marker.scale.y = 0.004;
//marker.scale.z = 0.004;
for(size_t i=0; i<input_xyz.points.size(); i++) {
std_msgs::ColorRGBA c;
// getting the collor of points[i]
c.r = (float)input_xyz.points[i].r/256;
c.g = (float)input_xyz.points[i].g/256;
c.b = (float)input_xyz.points[i].b/256;
// Do not forget to add a! This is actually very important!
c.a=1;
geometry_msgs::Point p;
p.x = input_xyz.points[i].x;
p.y = input_xyz.points[i].y;
p.z = input_xyz.points[i].z;
marker.points.push_back(p);
marker.colors.push_back(c);
}
pub.publish(marker);
}
int main(int argc, char** argv)
{
ros::init(argc, argv,"kinect");
ros::NodeHandle n;
pub= n.advertise<visualization_msgs::Marker>("marker",10);
pass_pub= n.advertise<sensor_msgs::PointCloud2>("filteredPnt",1);
ros::Subscriber sub= n.subscribe("kinect2/sd/points",1,cloud_cb);
ros::spin();
}
2 | No.2 Revision |
I could solve the problem by changing my prespective a little bit. So instead of moving the pointClouds, we can creat a Marker which is consisted of many points which have the same color as the points of the pointcloud and then we can move or rotate the frame of the marker. Here's a code for making the marker ( If anyone has any other recommendation I would be very happy to hear that!!):
#include<ros/ros.h>
#include<visualization_msgs/Marker.h>
#include<pcl-1.8/pcl/point_cloud.h>
#include<pcl_conversions/pcl_conversions.h>
#include<pcl-1.8/pcl/point_types.h>
#include <sensor_msgs/PointCloud.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_cloud_conversion.h>
#include<pcl-1.8/pcl/filters/passthrough.h>
ros::Publisher pub;
ros::Publisher pass_pub;
void cloud_cb(const pcl::PCLPointCloud2ConstPtr &input)
{
// Getting the target point cloud
pcl::PassThrough<pcl::PCLPointCloud2> pass;
pcl::PCLPointCloud2::Ptr flt_input(new pcl::PCLPointCloud2);
pass.setInputCloud(input);
pass.setFilterFieldName("x");
pass.setFilterLimits(0,2);
pass.filter(*flt_input);
pass.setInputCloud(flt_input);
pass.setFilterFieldName("y");
pass.setFilterLimits(-2,0);
pass.filter(*flt_input);
pass.setInputCloud(flt_input);
pass.setFilterFieldName("z");
pass.setFilterLimits(0,2);
pass.filter(*flt_input);
pass_pub.publish(*flt_input);
// Converting PointCloud2 to PointXYZRGBA
pcl::PointCloud<pcl::PointXYZRGBA> input_xyz;
pcl::fromPCLPointCloud2(*flt_input,input_xyz);
//create the marker
visualization_msgs::Marker marker;
marker.header.frame_id="/camera1";
marker.header.stamp=ros::Time::now();
marker.ns = "pcl_marker";
marker.id = 1;
marker.type = visualization_msgs::Marker::POINTS;
marker.action = visualization_msgs::Marker::ADD;
marker.lifetime = ros::Duration();
marker.scale.x = 0.004;
marker.scale.y = 0.004;
//marker.scale.z = 0.004;
for(size_t i=0; i<input_xyz.points.size(); i++) {
std_msgs::ColorRGBA c;
// getting the collor of points[i]
c.r = (float)input_xyz.points[i].r/256;
c.g = (float)input_xyz.points[i].g/256;
c.b = (float)input_xyz.points[i].b/256;
// Do not forget to add a! This is actually very important!
c.a=1;
geometry_msgs::Point p;
p.x = input_xyz.points[i].x;
p.y = input_xyz.points[i].y;
p.z = input_xyz.points[i].z;
marker.points.push_back(p);
marker.colors.push_back(c);
}
pub.publish(marker);
}
int main(int argc, char** argv)
{
ros::init(argc, argv,"kinect");
ros::NodeHandle n;
pub= n.advertise<visualization_msgs::Marker>("marker",10);
pass_pub= n.advertise<sensor_msgs::PointCloud2>("filteredPnt",1);
ros::Subscriber sub= n.subscribe("kinect2/sd/points",1,cloud_cb);
ros::spin();
}