The scan finder is useful for aligning a laser scanner with other sensors. In particular, the laser scan be multiplied in the Z direction in order to create a plane for plane to plane calibration. More...
#include <scan_finder.h>
Public Member Functions | |
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. It should add any new observations to the msg passed in. More... | |
virtual bool | init (const std::string &name, ros::NodeHandle &n) |
Initialize the feature finder. More... | |
ScanFinder () | |
virtual | ~ScanFinder ()=default |
![]() | |
FeatureFinder () | |
std::string | getName () |
Get the name of this feature finder. More... | |
virtual | ~FeatureFinder () |
Protected Member Functions | |
void | extractObservation (const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg) |
Extract the point cloud into a calibration message. More... | |
void | extractPoints (sensor_msgs::PointCloud2 &cloud) |
Extract a point cloud from laser scan points that meet criteria. More... | |
virtual void | scanCallback (const sensor_msgs::LaserScan &scan) |
ROS callback - updates scan_ and resets waiting_ to false. More... | |
virtual bool | waitForScan () |
Wait until a new scan has arrived. More... | |
Protected Attributes | |
std::string | laser_sensor_name_ |
double | max_x_ |
double | max_y_ |
double | min_x_ |
double | min_y_ |
bool | output_debug_ |
ros::Publisher | publisher_ |
sensor_msgs::LaserScan | scan_ |
ros::Subscriber | subscriber_ |
tf2_ros::Buffer | tf_buffer_ |
tf2_ros::TransformListener | tf_listener_ |
std::string | transform_frame_ |
bool | waiting_ |
double | z_offset_ |
int | z_repeats_ |
The scan finder is useful for aligning a laser scanner with other sensors. In particular, the laser scan be multiplied in the Z direction in order to create a plane for plane to plane calibration.
Definition at line 35 of file scan_finder.h.
robot_calibration::ScanFinder::ScanFinder | ( | ) |
Definition at line 36 of file scan_finder.cpp.
|
virtualdefault |
|
protected |
Extract the point cloud into a calibration message.
Definition at line 209 of file scan_finder.cpp.
|
protected |
Extract a point cloud from laser scan points that meet criteria.
Definition at line 128 of file scan_finder.cpp.
|
virtual |
Once the robot has been moved into the proper position and settled, this function will be called. It should add any new observations to the msg passed in.
msg | The message to which observations should be added. |
Implements robot_calibration::FeatureFinder.
Definition at line 111 of file scan_finder.cpp.
|
virtual |
Initialize the feature finder.
name | The name of this finder. |
nh | The nodehandle to use when loading feature finder configuration data. |
Reimplemented from robot_calibration::FeatureFinder.
Definition at line 41 of file scan_finder.cpp.
|
protectedvirtual |
ROS callback - updates scan_ and resets waiting_ to false.
Definition at line 82 of file scan_finder.cpp.
|
protectedvirtual |
Wait until a new scan has arrived.
Definition at line 91 of file scan_finder.cpp.
|
protected |
Definition at line 74 of file scan_finder.h.
|
protected |
Definition at line 76 of file scan_finder.h.
|
protected |
Definition at line 78 of file scan_finder.h.
|
protected |
Definition at line 75 of file scan_finder.h.
|
protected |
Definition at line 77 of file scan_finder.h.
|
protected |
Definition at line 83 of file scan_finder.h.
|
protected |
Definition at line 66 of file scan_finder.h.
|
protected |
Definition at line 72 of file scan_finder.h.
|
protected |
Definition at line 65 of file scan_finder.h.
|
protected |
Definition at line 68 of file scan_finder.h.
|
protected |
Definition at line 69 of file scan_finder.h.
|
protected |
Definition at line 81 of file scan_finder.h.
|
protected |
Definition at line 71 of file scan_finder.h.
|
protected |
Definition at line 80 of file scan_finder.h.
|
protected |
Definition at line 79 of file scan_finder.h.