scan_finder.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2022 Michael Ferguson
3  * Copyright (C) 2014-2017 Fetch Robotics Inc.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  */
17 
18 #ifndef ROBOT_CALIBRATION_CAPTURE_SCAN_FINDER_H
19 #define ROBOT_CALIBRATION_CAPTURE_SCAN_FINDER_H
20 
21 #include <ros/ros.h>
23 #include <robot_calibration_msgs/CalibrationData.h>
24 #include <sensor_msgs/LaserScan.h>
26 
27 namespace robot_calibration
28 {
35 class ScanFinder : public FeatureFinder
36 {
37 public:
38  ScanFinder();
39  virtual ~ScanFinder() = default;
40  virtual bool init(const std::string& name, ros::NodeHandle & n);
41  virtual bool find(robot_calibration_msgs::CalibrationData * msg);
42 
43 protected:
47  virtual void scanCallback(const sensor_msgs::LaserScan& scan);
48 
52  virtual bool waitForScan();
53 
57  void extractPoints(sensor_msgs::PointCloud2& cloud);
58 
62  void extractObservation(const sensor_msgs::PointCloud2& cloud,
63  robot_calibration_msgs::CalibrationData * msg);
64 
67 
70 
71  bool waiting_;
72  sensor_msgs::LaserScan scan_;
73 
74  std::string laser_sensor_name_;
75  double min_x_;
76  double max_x_;
77  double min_y_;
78  double max_y_;
80  double z_offset_;
81  std::string transform_frame_;
82 
84 };
85 
86 } // namespace robot_calibration
87 
88 #endif // ROBOT_CALIBRATION_CAPTURE_SCAN_FINDER_H
feature_finder.h
robot_calibration::ScanFinder::max_y_
double max_y_
Definition: scan_finder.h:78
robot_calibration::ScanFinder::output_debug_
bool output_debug_
Definition: scan_finder.h:83
ros::Publisher
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::~ScanFinder
virtual ~ScanFinder()=default
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
ros.h
robot_calibration::ScanFinder::scan_
sensor_msgs::LaserScan scan_
Definition: scan_finder.h:72
robot_calibration::ScanFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: scan_finder.cpp:41
robot_calibration::ScanFinder::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: scan_finder.h:69
robot_calibration::ScanFinder::publisher_
ros::Publisher publisher_
Definition: scan_finder.h:66
tf2_ros::TransformListener
robot_calibration::ScanFinder::min_x_
double min_x_
Definition: scan_finder.h:75
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
tf2_ros::Buffer
transform_listener.h
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
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
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
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
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
robot_calibration::ScanFinder::subscriber_
ros::Subscriber subscriber_
Definition: scan_finder.h:65
ros::NodeHandle
robot_calibration::ScanFinder::max_x_
double max_x_
Definition: scan_finder.h:76
ros::Subscriber


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