Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include <robot_calibration/capture/ground_plane_finder.h>
00019 #include <sensor_msgs/point_cloud2_iterator.h>
00020 #include <math.h>
00021
00022 namespace robot_calibration
00023 {
00024
00025 const unsigned X = 0;
00026 const unsigned Y = 1;
00027 const unsigned Z = 2;
00028
00029 GroundPlaneFinder::GroundPlaneFinder(ros::NodeHandle & nh) :
00030 FeatureFinder(nh),
00031 waiting_(false)
00032 {
00033 std::string topic_name;
00034 nh.param<std::string>("topic", topic_name, "/points");
00035 subscriber_ = nh.subscribe(topic_name,
00036 1,
00037 &GroundPlaneFinder::cameraCallback,
00038 this);
00039
00040 nh.param<std::string>("camera_sensor_name", camera_sensor_name_, "cameraground");
00041 nh.param<std::string>("chain_sensor_name", chain_sensor_name_, "ground");
00042 nh.param<double>("points_max", points_max_, 60);
00043 nh.param<double>("max_z", max_z_, 0);
00044
00045 publisher_ = nh.advertise<sensor_msgs::PointCloud2>("ground_plane_points", 10);
00046 if (!depth_camera_manager_.init(nh))
00047 {
00048
00049 throw;
00050 }
00051 }
00052
00053 void GroundPlaneFinder::cameraCallback(const sensor_msgs::PointCloud2& cloud)
00054 {
00055 if (waiting_)
00056 {
00057 cloud_ = cloud;
00058 waiting_ = false;
00059 }
00060 }
00061
00062 bool GroundPlaneFinder::waitForCloud()
00063 {
00064 ros::Duration(1/10.0).sleep();
00065
00066 waiting_ = true;
00067 int count = 250;
00068 while (--count)
00069 {
00070 if (!waiting_)
00071 {
00072
00073 return true;
00074 }
00075 ros::Duration(0.01).sleep();
00076 ros::spinOnce();
00077 }
00078 ROS_ERROR("Failed to get cloud");
00079 return !waiting_;
00080 }
00081
00082
00083 bool GroundPlaneFinder::find(robot_calibration_msgs::CalibrationData * msg)
00084 {
00085 geometry_msgs::PointStamped rgbd;
00086 geometry_msgs::PointStamped world;
00087
00088 if (!waitForCloud())
00089 {
00090 ROS_ERROR("No point cloud data");
00091 return false;
00092 }
00093
00094
00095 size_t num_points = cloud_.width * cloud_.height;
00096 sensor_msgs::PointCloud2ConstIterator<float> xyz(cloud_, "x");
00097 sensor_msgs::PointCloud2Iterator<float> iter(cloud_, "x");
00098
00099 size_t j = 0;
00100 for (size_t i = 0; i < num_points; i++)
00101 {
00102 geometry_msgs::Point p;
00103 p.x = (xyz + i)[X];
00104 p.y = (xyz + i)[Y];
00105 p.z = (xyz + i)[Z];
00106
00107 if (!std::isfinite(p.x) || !std::isfinite(p.y) || !std::isfinite(p.z))
00108 continue;
00109
00110 if (p.z >max_z_ && max_z_ != 0)
00111 continue;
00112 (iter + j)[X] = (xyz + i)[X];
00113 (iter + j)[Y] = (xyz + i)[Y];
00114 (iter + j)[Z] = (xyz + i)[Z];
00115 j++;
00116 }
00117
00118 cloud_.height = 1;
00119 cloud_.width = j;
00120 cloud_.data.resize(cloud_.width * cloud_.point_step);
00121
00122 size_t points_total = std::min(static_cast<size_t>(points_max_), j);
00123 std::vector<cv::Point2f> points;
00124 points.resize(points_total);
00125
00126
00127 sensor_msgs::PointCloud2 cloud;
00128 cloud.width = 0;
00129 cloud.height = 0;
00130 cloud.header.stamp = ros::Time::now();
00131 cloud.header.frame_id = cloud_.header.frame_id;
00132 sensor_msgs::PointCloud2Modifier cloud_mod(cloud);
00133 cloud_mod.setPointCloud2FieldsByString(1, "xyz");
00134 cloud_mod.resize(points_total);
00135 sensor_msgs::PointCloud2Iterator<float> iter_cloud(cloud_, "x");
00136
00137
00138 int idx_cam = msg->observations.size() + 0;
00139 int idx_chain = msg->observations.size() + 1;
00140 msg->observations.resize(msg->observations.size() + 2);
00141 msg->observations[idx_cam].sensor_name = camera_sensor_name_;
00142 msg->observations[idx_chain].sensor_name = chain_sensor_name_;
00143
00144 msg->observations[idx_cam].features.resize(points_total);
00145 msg->observations[idx_chain].features.resize(points_total);
00146
00147 size_t step = cloud_.width/(points_total);
00148 size_t k = 0;
00149
00150 for (size_t i = step; i < cloud_.width && k < points_total; i += step)
00151 {
00152 points[k].x = i;
00153 k++;
00154 }
00155
00156 for (size_t i = 0; i < points.size(); i++)
00157 {
00158
00159 world.point.x = 0;
00160 world.point.y = 0;
00161 world.point.z = 0;
00162
00163
00164 int index = static_cast<int>(points[i].x);
00165 rgbd.point.x = (xyz + index)[X];
00166 rgbd.point.y = (xyz + index)[Y];
00167 rgbd.point.z = (xyz + index)[Z];
00168 msg->observations[idx_cam].features[i] = rgbd;
00169 msg->observations[idx_cam].ext_camera_info = depth_camera_manager_.getDepthCameraInfo();
00170 msg->observations[idx_chain].features[i] = world;
00171
00172 iter_cloud[0] = rgbd.point.x;
00173 iter_cloud[1] = rgbd.point.y;
00174 iter_cloud[2] = rgbd.point.z;
00175 ++iter_cloud;
00176 }
00177
00178 publisher_.publish(cloud);
00179 return true;
00180 }
00181 }