robot_finder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2015-2017 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Niharika Arora, Michael Ferguson
20 
21 #include <math.h>
26 
28 
29 namespace robot_calibration
30 {
31 
32 const unsigned X = 0;
33 const unsigned Y = 1;
34 const unsigned Z = 2;
35 
37  PlaneFinder()
38 {
39 }
40 
41 bool RobotFinder::init(const std::string& name,
42  ros::NodeHandle & nh)
43 {
44  if (!PlaneFinder::init(name, nh))
45  return false;
46 
47  // Name of the sensor model that will be used during optimization
48  nh.param<std::string>("robot_sensor_name", robot_sensor_name_, "camera_robot");
49 
50  // Publish the observation as a PointCloud2
51  robot_publisher_ = nh.advertise<sensor_msgs::PointCloud2>(getName() + "_robot_points", 10);
52 
53  // Valid points must lie within this box, in the transform_frame
54  nh.param<double>("min_robot_x", min_robot_x_, -2.0);
55  nh.param<double>("max_robot_x", max_robot_x_, 2.0);
56  nh.param<double>("min_robot_y", min_robot_y_, -2.0);
57  nh.param<double>("max_robot_y", max_robot_y_, 2.0);
58  nh.param<double>("min_robot_z", min_robot_z_, 0.0);
59  nh.param<double>("max_robot_z", max_robot_z_, 2.0);
60 
61  return true;
62 }
63 
64 bool RobotFinder::find(robot_calibration_msgs::CalibrationData * msg)
65 {
66  if (!waitForCloud())
67  {
68  ROS_ERROR("No point cloud data");
69  return false;
70  }
71 
72  // Remove invalid points
74 
75  // Find the ground plane and extract it
76  sensor_msgs::PointCloud2 plane = extractPlane(cloud_);
77 
78  // Remove anything that isn't the robot from the cloud
81 
82  // Pull out both sets of observations
85 
86  // Report success
87  return true;
88 }
89 
90 } // namespace robot_calibration
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
point_cloud2_iterator.h
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
robot_calibration::Y
const unsigned Y
Definition: checkerboard_finder.cpp:33
robot_calibration::X
const unsigned X
Definition: checkerboard_finder.cpp:32
robot_calibration::RobotFinder::max_robot_y_
double max_robot_y_
Definition: robot_finder.h:45
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
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::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
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
robot_calibration::RobotFinder::min_robot_z_
double min_robot_z_
Definition: robot_finder.h:46
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::RobotFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: robot_finder.cpp:41
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
robot_calibration::PlaneFinder::plane_sensor_name_
std::string plane_sensor_name_
Definition: plane_finder.h:96
name
std::string name
robot_calibration::RobotFinder
Definition: robot_finder.h:27
ROS_ERROR
#define ROS_ERROR(...)
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
robot_calibration::Z
const unsigned Z
Definition: checkerboard_finder.cpp:34
robot_calibration::FeatureFinder::getName
std::string getName()
Get the name of this feature finder.
Definition: feature_finder.h:57
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::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
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2_geometry_msgs.h
robot_finder.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::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