scan_finder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2015-2017 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Michael Ferguson
20 
21 #include <math.h>
26 
28 
29 namespace robot_calibration
30 {
31 
32 const unsigned X = 0;
33 const unsigned Y = 1;
34 const unsigned Z = 2;
35 
37  tf_listener_(tf_buffer_), waiting_(false)
38 {
39 }
40 
41 bool ScanFinder::init(const std::string& name,
42  ros::NodeHandle & nh)
43 {
44  if (!FeatureFinder::init(name, nh))
45  return false;
46 
47  // We subscribe to a LaserScan
48  std::string topic_name;
49  nh.param<std::string>("topic", topic_name, "/scan");
50  subscriber_ = nh.subscribe(topic_name,
51  1,
53  this);
54 
55  // Name of the sensor model that will be used during optimization
56  nh.param<std::string>("sensor_name", laser_sensor_name_, "laser");
57 
58  // Frame to transform point cloud into before applying limits below
59  // if specified as "none", cloud will be processed in sensor frame
60  nh.param<std::string>("transform_frame", transform_frame_, "base_link");
61 
62  // It is assumed that the laser scanner operates in the X,Y plane
63  // Valid points must lie within this box, in the laser frame
64  nh.param<double>("min_x", min_x_, -2.0);
65  nh.param<double>("max_x", max_x_, 2.0);
66  nh.param<double>("min_y", min_y_, -2.0);
67  nh.param<double>("max_y", max_y_, 2.0);
68 
69  // Repeat points in the Z plane a number of times at fixed distance
70  nh.param<int>("z_repeats", z_repeats_, 10);
71  nh.param<double>("z_offset", z_offset_, 0.1);
72 
73  // Should we include debug image/cloud in observations
74  nh.param<bool>("debug", output_debug_, false);
75 
76  // Publish the observation as a PointCloud2
77  publisher_ = nh.advertise<sensor_msgs::PointCloud2>(getName() + "_points", 10);
78 
79  return true;
80 }
81 
82 void ScanFinder::scanCallback(const sensor_msgs::LaserScan& scan)
83 {
84  if (waiting_)
85  {
86  scan_ = scan;
87  waiting_ = false;
88  }
89 }
90 
92 {
93  ros::Duration(1/10.0).sleep();
94 
95  waiting_ = true;
96  int count = 250;
97  while (--count)
98  {
99  if (!waiting_)
100  {
101  // success
102  return true;
103  }
104  ros::Duration(0.01).sleep();
105  ros::spinOnce();
106  }
107  ROS_ERROR("Failed to get scan");
108  return !waiting_;
109 }
110 
111 bool ScanFinder::find(robot_calibration_msgs::CalibrationData * msg)
112 {
113  if (!waitForScan())
114  {
115  ROS_ERROR("No laser scan data");
116  return false;
117  }
118 
119  // Extract the points corresponding to the line
120  sensor_msgs::PointCloud2 cloud;
121  extractPoints(cloud);
122  extractObservation(cloud, msg);
123 
124  // Report success
125  return true;
126 }
127 
128 void ScanFinder::extractPoints(sensor_msgs::PointCloud2& cloud)
129 {
130  bool do_transform = transform_frame_ != "none";
131 
132  // Reset cloud
133  cloud.width = 0;
134  cloud.height = 0;
135  cloud.header.stamp = ros::Time::now();
136  cloud.header.frame_id = do_transform ? transform_frame_ : scan_.header.frame_id;
137 
138  // Setup cloud to be XYZ
139  sensor_msgs::PointCloud2Modifier cloud_mod(cloud);
140  cloud_mod.setPointCloud2FieldsByString(1, "xyz");
141  cloud_mod.resize(scan_.ranges.size() * z_repeats_);
142 
143  // Create iterator to edit cloud
144  sensor_msgs::PointCloud2Iterator<float> cloud_iter(cloud, "x");
145 
146  // Filter and transform scan points
147  size_t line_point_count = 0;
148  for (size_t i = 0; i < scan_.ranges.size(); ++i)
149  {
150  // Remove any NaNs in scan
151  if (!std::isfinite(scan_.ranges[i]))
152  {
153  continue;
154  }
155 
156  // Geometry to convert from scan to cloud
157  double angle = scan_.angle_min + (i * scan_.angle_increment);
158 
159  // Create point (in sensor frame)
160  geometry_msgs::PointStamped p;
161  p.point.x = cos(angle) * scan_.ranges[i];
162  p.point.y = sin(angle) * scan_.ranges[i];
163  p.point.z = 0.0;
164 
165  // Test the transformed point
166  if (p.point.x < min_x_ || p.point.x > max_x_ || p.point.y < min_y_ || p.point.y > max_y_)
167  {
168  continue;
169  }
170 
171  // Get transform (if any)
172  for (int z = 0; z < z_repeats_; ++z)
173  {
174  geometry_msgs::PointStamped p_out;
175  if (do_transform)
176  {
177  p.header.stamp = ros::Time(0);
178  p.header.frame_id = scan_.header.frame_id;
179  p.point.z = z * z_offset_;
180  try
181  {
183  }
184  catch (tf2::TransformException& ex)
185  {
186  ROS_ERROR("%s", ex.what());
187  ros::Duration(1.0).sleep();
188  continue;
189  }
190  }
191  else
192  {
193  p_out = p;
194  }
195 
196  // This is a valid point, move it forward
197  (cloud_iter + line_point_count)[X] = p_out.point.x;
198  (cloud_iter + line_point_count)[Y] = p_out.point.y;
199  (cloud_iter + line_point_count)[Z] = p_out.point.z;
200  ++line_point_count;
201  }
202  }
203 
204  // Resize clouds
205  cloud.height = 1;
206  cloud.width = line_point_count;
207 }
208 
209 void ScanFinder::extractObservation(const sensor_msgs::PointCloud2& cloud,
210  robot_calibration_msgs::CalibrationData * msg)
211 {
212  if (static_cast<int>(cloud.width) == 0)
213  {
214  ROS_WARN("No points in observation, skipping");
215  return;
216  }
217 
218  ROS_INFO_STREAM("Got " << cloud.width << " points for observation");
219 
220  // Create PointCloud2 to publish
221  sensor_msgs::PointCloud2 viz_cloud;
222  viz_cloud.width = 0;
223  viz_cloud.height = 0;
224  viz_cloud.header.stamp = ros::Time::now();
225  viz_cloud.header.frame_id = cloud.header.frame_id;
226  sensor_msgs::PointCloud2Modifier cloud_mod(viz_cloud);
227  cloud_mod.setPointCloud2FieldsByString(1, "xyz");
228  cloud_mod.resize(cloud.width);
229 
230  // Setup observation
231  int idx_cam = msg->observations.size();
232  msg->observations.resize(msg->observations.size() + 1);
233  msg->observations[idx_cam].sensor_name = laser_sensor_name_;
234 
235  // Fill in observation
236  sensor_msgs::PointCloud2Iterator<float> viz_cloud_iter(viz_cloud, "x");
238  for (size_t i = 0; i < cloud.width; ++i)
239  {
240  // Get 3d point
241  geometry_msgs::PointStamped rgbd;
242  rgbd.point.x = (xyz + i)[X];
243  rgbd.point.y = (xyz + i)[Y];
244  rgbd.point.z = (xyz + i)[Z];
245 
246  // Add to observation
247  msg->observations[idx_cam].features.push_back(rgbd);
248 
249  // Copy to cloud for publishing
250  viz_cloud_iter[0] = rgbd.point.x;
251  viz_cloud_iter[1] = rgbd.point.y;
252  viz_cloud_iter[2] = rgbd.point.z;
253  ++viz_cloud_iter;
254  }
255 
256  // Add debug cloud to message
257  if (output_debug_)
258  {
259  msg->observations[idx_cam].cloud = cloud;
260  }
261 
262  // Publish debug info
263  publisher_.publish(viz_cloud);
264 }
265 
266 } // namespace robot_calibration
robot_calibration::ScanFinder::max_y_
double max_y_
Definition: scan_finder.h:78
point_cloud2_iterator.h
robot_calibration::ScanFinder::output_debug_
bool output_debug_
Definition: scan_finder.h:83
robot_calibration::Y
const unsigned Y
Definition: checkerboard_finder.cpp:33
robot_calibration::X
const unsigned X
Definition: checkerboard_finder.cpp:32
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
robot_calibration::ScanFinder::find
virtual bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called....
Definition: scan_finder.cpp:111
robot_calibration::ScanFinder::laser_sensor_name_
std::string laser_sensor_name_
Definition: scan_finder.h:74
robot_calibration::ScanFinder::waiting_
bool waiting_
Definition: scan_finder.h:71
robot_calibration::FeatureFinder
Base class for a feature finder.
Definition: feature_finder.h:33
robot_calibration::ScanFinder::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: scan_finder.h:68
robot_calibration::ScanFinder::ScanFinder
ScanFinder()
Definition: scan_finder.cpp:36
robot_calibration::ScanFinder
The scan finder is useful for aligning a laser scanner with other sensors. In particular,...
Definition: scan_finder.h:35
robot_calibration::ScanFinder::scan_
sensor_msgs::LaserScan scan_
Definition: scan_finder.h:72
ros::spinOnce
ROSCPP_DECL void spinOnce()
robot_calibration::ScanFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: scan_finder.cpp:41
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
sensor_msgs::PointCloud2ConstIterator
robot_calibration::ScanFinder::publisher_
ros::Publisher publisher_
Definition: scan_finder.h:66
robot_calibration::ScanFinder::min_x_
double min_x_
Definition: scan_finder.h:75
sensor_msgs::PointCloud2Iterator
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
name
std::string name
robot_calibration::ScanFinder::extractPoints
void extractPoints(sensor_msgs::PointCloud2 &cloud)
Extract a point cloud from laser scan points that meet criteria.
Definition: scan_finder.cpp:128
robot_calibration::ScanFinder::min_y_
double min_y_
Definition: scan_finder.h:77
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
scan_finder.h
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
robot_calibration::FeatureFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
Definition: feature_finder.h:47
robot_calibration::Z
const unsigned Z
Definition: checkerboard_finder.cpp:34
robot_calibration::FeatureFinder::getName
std::string getName()
Get the name of this feature finder.
Definition: feature_finder.h:57
tf2_ros::BufferInterface::transform
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
robot_calibration::ScanFinder::scanCallback
virtual void scanCallback(const sensor_msgs::LaserScan &scan)
ROS callback - updates scan_ and resets waiting_ to false.
Definition: scan_finder.cpp:82
ros::Time
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
sensor_msgs::PointCloud2Modifier
class_list_macros.hpp
robot_calibration::ScanFinder::extractObservation
void extractObservation(const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg)
Extract the point cloud into a calibration message.
Definition: scan_finder.cpp:209
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2_geometry_msgs.h
robot_calibration::ScanFinder::z_repeats_
int z_repeats_
Definition: scan_finder.h:79
robot_calibration::ScanFinder::waitForScan
virtual bool waitForScan()
Wait until a new scan has arrived.
Definition: scan_finder.cpp:91
ros::Duration::sleep
bool sleep() const
robot_calibration::ScanFinder::z_offset_
double z_offset_
Definition: scan_finder.h:80
robot_calibration::ScanFinder::transform_frame_
std::string transform_frame_
Definition: scan_finder.h:81
tf2::TransformException
robot_calibration::ScanFinder::subscriber_
ros::Subscriber subscriber_
Definition: scan_finder.h:65
ros::Duration
z
double z
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
ros::NodeHandle
robot_calibration::ScanFinder::max_x_
double max_x_
Definition: scan_finder.h:76
ros::Time::now
static Time now()


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01