plane_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_PLANE_FINDER_H
19 #define ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
20 
21 #include <ros/ros.h>
25 #include <robot_calibration_msgs/CalibrationData.h>
26 #include <cv_bridge/cv_bridge.h>
28 
29 namespace robot_calibration
30 {
34 class PlaneFinder : public FeatureFinder
35 {
36 public:
37  PlaneFinder();
38  virtual ~PlaneFinder() = default;
39  virtual bool init(const std::string& name, ros::NodeHandle & n);
40  virtual bool find(robot_calibration_msgs::CalibrationData * msg);
41 
42 protected:
46  virtual void cameraCallback(const sensor_msgs::PointCloud2& cloud);
47 
58  virtual void removeInvalidPoints(sensor_msgs::PointCloud2& cloud,
59  double min_x, double max_x, double min_y, double max_y, double min_z, double max_z);
60 
66  virtual sensor_msgs::PointCloud2 extractPlane(sensor_msgs::PointCloud2& cloud);
67 
75  virtual void extractObservation(const std::string& sensor_name,
76  const sensor_msgs::PointCloud2& cloud,
77  robot_calibration_msgs::CalibrationData * msg,
78  ros::Publisher* publisher);
79 
83  virtual bool waitForCloud();
84 
87 
90 
91  bool waiting_;
92  sensor_msgs::PointCloud2 cloud_;
94 
95  // See init() function for parameter definitions
96  std::string plane_sensor_name_;
100  double min_x_, max_x_;
101  double min_y_, max_y_;
102  double min_z_, max_z_;
103  Eigen::Vector3d desired_normal_;
105  std::string transform_frame_;
108 
110 };
111 
112 } // namespace robot_calibration
113 
114 #endif // ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
tf2_ros::TransformListener tf_listener_
Definition: plane_finder.h:89
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Base class for a feature finder.
DepthCameraInfoManager depth_camera_manager_
Definition: plane_finder.h:93
virtual void removeInvalidPoints(sensor_msgs::PointCloud2 &cloud, double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)
Remove invalid points from a cloud.
virtual sensor_msgs::PointCloud2 extractPlane(sensor_msgs::PointCloud2 &cloud)
Extract a plane from the point cloud.
sensor_msgs::PointCloud2 cloud_
Definition: plane_finder.h:92
virtual bool waitForCloud()
Wait until a new cloud has arrived.
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...
Calibration code lives under this namespace.
Base class for a feature finder.
Definition: depth_camera.h:32
virtual ~PlaneFinder()=default
virtual void extractObservation(const std::string &sensor_name, const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg, ros::Publisher *publisher)
Extract points from a cloud into a calibration message.
Finds the largest plane in a point cloud.
Definition: plane_finder.h:34
virtual void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
ROS callback - updates cloud_ and resets waiting_ to false.


robot_calibration
Author(s): Michael Ferguson
autogenerated on Wed May 24 2023 02:30:23