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
robot_calibration::PlaneFinder::cos_normal_angle_
double cos_normal_angle_
Definition: plane_finder.h:104
robot_calibration::PlaneFinder::output_debug_
bool output_debug_
Definition: plane_finder.h:109
feature_finder.h
robot_calibration::PlaneFinder::waiting_
bool waiting_
Definition: plane_finder.h:91
robot_calibration::PlaneFinder::publisher_
ros::Publisher publisher_
Definition: plane_finder.h:86
robot_calibration::PlaneFinder
Finds the largest plane in a point cloud.
Definition: plane_finder.h:34
robot_calibration::PlaneFinder::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: plane_finder.h:89
robot_calibration::PlaneFinder::points_max_
int points_max_
Definition: plane_finder.h:97
ros::Publisher
depth_camera.h
robot_calibration::FeatureFinder
Base class for a feature finder.
Definition: feature_finder.h:33
robot_calibration::PlaneFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: plane_finder.cpp:96
ros.h
robot_calibration::DepthCameraInfoManager
Base class for a feature finder.
Definition: depth_camera.h:32
robot_calibration::PlaneFinder::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: plane_finder.h:88
robot_calibration::PlaneFinder::max_x_
double max_x_
Definition: plane_finder.h:100
robot_calibration::PlaneFinder::min_z_
double min_z_
Definition: plane_finder.h:102
robot_calibration::PlaneFinder::removeInvalidPoints
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.
Definition: plane_finder.cpp:210
robot_calibration::PlaneFinder::~PlaneFinder
virtual ~PlaneFinder()=default
robot_calibration::PlaneFinder::depth_camera_manager_
DepthCameraInfoManager depth_camera_manager_
Definition: plane_finder.h:93
robot_calibration::PlaneFinder::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: plane_finder.cpp:194
tf2_ros::TransformListener
robot_calibration::PlaneFinder::max_z_
double max_z_
Definition: plane_finder.h:102
robot_calibration::PlaneFinder::min_y_
double min_y_
Definition: plane_finder.h:101
robot_calibration::PlaneFinder::initial_sampling_distance_
double initial_sampling_distance_
Definition: plane_finder.h:98
robot_calibration::PlaneFinder::subscriber_
ros::Subscriber subscriber_
Definition: plane_finder.h:85
robot_calibration::PlaneFinder::desired_normal_
Eigen::Vector3d desired_normal_
Definition: plane_finder.h:103
robot_calibration::PlaneFinder::ransac_points_
int ransac_points_
Definition: plane_finder.h:107
eigen_geometry.h
robot_calibration::PlaneFinder::plane_sensor_name_
std::string plane_sensor_name_
Definition: plane_finder.h:96
name
std::string name
robot_calibration::PlaneFinder::cameraCallback
virtual void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
ROS callback - updates cloud_ and resets waiting_ to false.
Definition: plane_finder.cpp:165
robot_calibration::PlaneFinder::transform_frame_
std::string transform_frame_
Definition: plane_finder.h:105
tf2_ros::Buffer
robot_calibration::PlaneFinder::waitForCloud
virtual bool waitForCloud()
Wait until a new cloud has arrived.
Definition: plane_finder.cpp:174
robot_calibration::PlaneFinder::cloud_
sensor_msgs::PointCloud2 cloud_
Definition: plane_finder.h:92
robot_calibration::PlaneFinder::min_x_
double min_x_
Definition: plane_finder.h:100
transform_listener.h
robot_calibration::PlaneFinder::ransac_iterations_
int ransac_iterations_
Definition: plane_finder.h:106
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::PlaneFinder::max_y_
double max_y_
Definition: plane_finder.h:101
robot_calibration::PlaneFinder::extractObservation
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.
Definition: plane_finder.cpp:424
cv_bridge.h
robot_calibration::PlaneFinder::extractPlane
virtual sensor_msgs::PointCloud2 extractPlane(sensor_msgs::PointCloud2 &cloud)
Extract a plane from the point cloud.
Definition: plane_finder.cpp:280
robot_calibration::PlaneFinder::PlaneFinder
PlaneFinder()
Definition: plane_finder.cpp:91
robot_calibration::PlaneFinder::plane_tolerance_
double plane_tolerance_
Definition: plane_finder.h:99
ros::NodeHandle
ros::Subscriber


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