plane_finder.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014-2017 Fetch Robotics Inc.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
18 #define ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
19 
20 #include <ros/ros.h>
23 #include <robot_calibration_msgs/CalibrationData.h>
24 #include <cv_bridge/cv_bridge.h>
26 
27 namespace robot_calibration
28 {
29 
30 class PlaneFinder : public FeatureFinder
31 {
32 public:
33  PlaneFinder();
34  bool init(const std::string& name, ros::NodeHandle & n);
35  bool find(robot_calibration_msgs::CalibrationData * msg);
36 
37 private:
38  void cameraCallback(const sensor_msgs::PointCloud2& cloud);
39  bool waitForCloud();
40 
43 
46 
47  bool waiting_;
48  sensor_msgs::PointCloud2 cloud_;
50 
51  std::string camera_sensor_name_;
52  double points_max_;
53  double min_x_;
54  double max_x_;
55  double min_y_;
56  double max_y_;
57  double min_z_;
58  double max_z_;
59  std::string transform_frame_;
60 
62 };
63 
64 } // namespace robot_calibration
65 
66 #endif // ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
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:49
sensor_msgs::PointCloud2 cloud_
Definition: plane_finder.h:48
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
tf2_ros::TransformListener tfListener_
Definition: plane_finder.h:45
void cameraCallback(const sensor_msgs::PointCloud2 &cloud)


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30