robot_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_ROBOT_FINDER_H
19 #define ROBOT_CALIBRATION_CAPTURE_ROBOT_FINDER_H
20 
21 #include <ros/ros.h>
23 
24 namespace robot_calibration
25 {
26 
27 class RobotFinder : public PlaneFinder
28 {
29 public:
30  RobotFinder();
31  virtual ~RobotFinder() = default;
32  virtual bool init(const std::string& name, ros::NodeHandle & n);
33  virtual bool find(robot_calibration_msgs::CalibrationData * msg);
34 
35 protected:
36  // Observation name for robot points
37  std::string robot_sensor_name_;
38 
39  // Publisher for robot points debugging
41 
42  double min_robot_x_;
43  double max_robot_x_;
44  double min_robot_y_;
45  double max_robot_y_;
46  double min_robot_z_;
47  double max_robot_z_;
48 };
49 
50 } // namespace robot_calibration
51 
52 #endif // ROBOT_CALIBRATION_CAPTURE_ROBOT_FINDER_H
robot_calibration::PlaneFinder
Finds the largest plane in a point cloud.
Definition: plane_finder.h:34
robot_calibration::RobotFinder::min_robot_x_
double min_robot_x_
Definition: robot_finder.h:42
robot_calibration::RobotFinder::RobotFinder
RobotFinder()
Definition: robot_finder.cpp:36
ros::Publisher
robot_calibration::RobotFinder::max_robot_y_
double max_robot_y_
Definition: robot_finder.h:45
ros.h
robot_calibration::RobotFinder::~RobotFinder
virtual ~RobotFinder()=default
robot_calibration::RobotFinder::robot_publisher_
ros::Publisher robot_publisher_
Definition: robot_finder.h:40
robot_calibration::RobotFinder::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: robot_finder.cpp:64
robot_calibration::RobotFinder::robot_sensor_name_
std::string robot_sensor_name_
Definition: robot_finder.h:37
robot_calibration::RobotFinder::min_robot_z_
double min_robot_z_
Definition: robot_finder.h:46
robot_calibration::RobotFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: robot_finder.cpp:41
name
std::string name
plane_finder.h
robot_calibration::RobotFinder
Definition: robot_finder.h:27
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::RobotFinder::max_robot_x_
double max_robot_x_
Definition: robot_finder.h:43
robot_calibration::RobotFinder::max_robot_z_
double max_robot_z_
Definition: robot_finder.h:47
ros::NodeHandle
robot_calibration::RobotFinder::min_robot_y_
double min_robot_y_
Definition: robot_finder.h:44


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