led_finder.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Fetch Robotics Inc.
3  * Copyright (C) 2013-2014 Unbounded 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 // Author: Michael Ferguson
19 
20 #ifndef ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H
21 #define ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H
22 
23 #include <ros/ros.h>
26 
27 #include <tf/transform_listener.h>
28 #include <sensor_msgs/Image.h>
29 #include <sensor_msgs/PointCloud2.h>
30 #include <geometry_msgs/PointStamped.h>
31 #include <robot_calibration_msgs/CalibrationData.h>
32 #include <robot_calibration_msgs/GripperLedCommandAction.h>
34 
35 namespace robot_calibration
36 {
37 
39 class LedFinder : public FeatureFinder
40 {
43  {
44 
45  CloudDifferenceTracker(std::string frame, double x, double y, double z);
46 
57  bool process(sensor_msgs::PointCloud2& cloud,
58  sensor_msgs::PointCloud2& prev,
59  geometry_msgs::Point& led_point,
60  double max_distance,
61  double weight);
62 
63  // Have we found the LED?
64  bool isFound(const sensor_msgs::PointCloud2& cloud,
65  double threshold);
66 
67  // Gives a refined centroid using multiple points
68  bool getRefinedCentroid(const sensor_msgs::PointCloud2& cloud,
69  geometry_msgs::PointStamped& centroid);
70 
71  // Reset the tracker
72  void reset(size_t height, size_t width);
73 
74  // Get an image of tracker status
75  sensor_msgs::Image getImage();
76 
77  std::vector<double> diff_;
78  double max_;
79  int max_idx_;
80  int count_;
81  size_t height_, width_;
82  std::string frame_; // frame of led coordinates
83  geometry_msgs::Point point_; //coordinates of led this is tracking
84  };
85 
87 
88 public:
89  LedFinder();
90  bool init(const std::string& name, ros::NodeHandle & n);
91  bool find(robot_calibration_msgs::CalibrationData * msg);
92 
93 private:
94  void cameraCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud);
95  bool waitForCloud();
96 
99  boost::scoped_ptr<LedClient> client_;
100 
101  bool waiting_;
102  sensor_msgs::PointCloud2 cloud_;
103 
104  std::vector<boost::shared_ptr<ros::Publisher> > tracker_publishers_;
105  std::vector<CloudDifferenceTracker> trackers_;
106  std::vector<uint8_t> codes_;
107 
110 
111  /*
112  * ROS Parameters
113  */
114  double max_error_;
116 
117  double threshold_;
119 
121 
122  std::string camera_sensor_name_;
123  std::string chain_sensor_name_;
124 };
125 
126 } // namespace robot_calibration
127 
128 #endif // ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H
robot_calibration::LedFinder::CloudDifferenceTracker::isFound
bool isFound(const sensor_msgs::PointCloud2 &cloud, double threshold)
Definition: led_finder.cpp:455
robot_calibration::LedFinder::client_
boost::scoped_ptr< LedClient > client_
Outgoing sensor_msgs::PointCloud2.
Definition: led_finder.h:99
robot_calibration::LedFinder::waitForCloud
bool waitForCloud()
Definition: led_finder.cpp:136
feature_finder.h
robot_calibration::LedFinder::CloudDifferenceTracker::frame_
std::string frame_
Definition: led_finder.h:82
robot_calibration::LedFinder
This class processes the point cloud input to find the LED.
Definition: led_finder.h:39
robot_calibration::LedFinder::publisher_
ros::Publisher publisher_
Incoming sensor_msgs::PointCloud2.
Definition: led_finder.h:98
ros::Publisher
robot_calibration::LedFinder::CloudDifferenceTracker::CloudDifferenceTracker
CloudDifferenceTracker(std::string frame, double x, double y, double z)
Definition: led_finder.cpp:348
robot_calibration::LedFinder::LedClient
actionlib::SimpleActionClient< robot_calibration_msgs::GripperLedCommandAction > LedClient
Definition: led_finder.h:86
robot_calibration::LedFinder::CloudDifferenceTracker
Internally used within LED finder to track each of several LEDs.
Definition: led_finder.h:42
depth_camera.h
robot_calibration::FeatureFinder
Base class for a feature finder.
Definition: feature_finder.h:33
ros.h
robot_calibration::DepthCameraInfoManager
Base class for a feature finder.
Definition: depth_camera.h:32
robot_calibration::LedFinder::camera_sensor_name_
std::string camera_sensor_name_
Should we output debug image/cloud?
Definition: led_finder.h:122
robot_calibration::LedFinder::listener_
tf::TransformListener listener_
Definition: led_finder.h:108
robot_calibration::LedFinder::CloudDifferenceTracker::getImage
sensor_msgs::Image getImage()
Definition: led_finder.cpp:544
robot_calibration::LedFinder::CloudDifferenceTracker::process
bool process(sensor_msgs::PointCloud2 &cloud, sensor_msgs::PointCloud2 &prev, geometry_msgs::Point &led_point, double max_distance, double weight)
Update the tracker based on new cloud compared to previous.
Definition: led_finder.cpp:379
robot_calibration::LedFinder::cameraCallback
void cameraCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
Definition: led_finder.cpp:126
robot_calibration::LedFinder::max_error_
double max_error_
Definition: led_finder.h:114
robot_calibration::LedFinder::find
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: led_finder.cpp:157
robot_calibration::LedFinder::CloudDifferenceTracker::width_
size_t width_
Definition: led_finder.h:81
robot_calibration::LedFinder::depth_camera_manager_
DepthCameraInfoManager depth_camera_manager_
Definition: led_finder.h:109
actionlib::SimpleActionClient
robot_calibration::LedFinder::output_debug_
bool output_debug_
Maximum number of cycles before we abort finding the LED.
Definition: led_finder.h:120
robot_calibration::LedFinder::CloudDifferenceTracker::height_
size_t height_
Definition: led_finder.h:81
simple_action_client.h
robot_calibration::LedFinder::CloudDifferenceTracker::max_
double max_
Definition: led_finder.h:78
robot_calibration::LedFinder::init
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: led_finder.cpp:53
robot_calibration::LedFinder::LedFinder
LedFinder()
Definition: led_finder.cpp:48
y
double y
prev
EndPoint * prev[3]
robot_calibration::LedFinder::trackers_
std::vector< CloudDifferenceTracker > trackers_
Definition: led_finder.h:105
robot_calibration::LedFinder::chain_sensor_name_
std::string chain_sensor_name_
Definition: led_finder.h:123
robot_calibration::LedFinder::codes_
std::vector< uint8_t > codes_
Definition: led_finder.h:106
robot_calibration::LedFinder::max_iterations_
int max_iterations_
Minimum value of diffs in order to trigger that this is an LED.
Definition: led_finder.h:118
robot_calibration::LedFinder::CloudDifferenceTracker::point_
geometry_msgs::Point point_
Definition: led_finder.h:83
robot_calibration::LedFinder::tracker_publishers_
std::vector< boost::shared_ptr< ros::Publisher > > tracker_publishers_
Definition: led_finder.h:104
transform_listener.h
robot_calibration::LedFinder::CloudDifferenceTracker::diff_
std::vector< double > diff_
Definition: led_finder.h:77
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::LedFinder::CloudDifferenceTracker::max_idx_
int max_idx_
Definition: led_finder.h:79
tf::TransformListener
robot_calibration::LedFinder::waiting_
bool waiting_
Definition: led_finder.h:101
x
double x
robot_calibration::LedFinder::CloudDifferenceTracker::getRefinedCentroid
bool getRefinedCentroid(const sensor_msgs::PointCloud2 &cloud, geometry_msgs::PointStamped &centroid)
Definition: led_finder.cpp:480
robot_calibration::LedFinder::CloudDifferenceTracker::reset
void reset(size_t height, size_t width)
Definition: led_finder.cpp:357
robot_calibration::LedFinder::cloud_
sensor_msgs::PointCloud2 cloud_
Definition: led_finder.h:102
robot_calibration::LedFinder::max_inconsistency_
double max_inconsistency_
Maximum distance led can be from expected pose.
Definition: led_finder.h:115
robot_calibration::LedFinder::subscriber_
ros::Subscriber subscriber_
Definition: led_finder.h:97
z
double z
ros::NodeHandle
ros::Subscriber
robot_calibration::LedFinder::CloudDifferenceTracker::count_
int count_
Definition: led_finder.h:80
robot_calibration::LedFinder::threshold_
double threshold_
Definition: led_finder.h:117


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