Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
robot_calibration::ScanFinder Class Reference

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>

Inheritance diagram for robot_calibration::ScanFinder:
Inheritance graph
[legend]

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
 
- Public Member Functions inherited from robot_calibration::FeatureFinder
 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_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ScanFinder()

robot_calibration::ScanFinder::ScanFinder ( )

Definition at line 36 of file scan_finder.cpp.

◆ ~ScanFinder()

virtual robot_calibration::ScanFinder::~ScanFinder ( )
virtualdefault

Member Function Documentation

◆ extractObservation()

void robot_calibration::ScanFinder::extractObservation ( const sensor_msgs::PointCloud2 &  cloud,
robot_calibration_msgs::CalibrationData *  msg 
)
protected

Extract the point cloud into a calibration message.

Definition at line 209 of file scan_finder.cpp.

◆ extractPoints()

void robot_calibration::ScanFinder::extractPoints ( sensor_msgs::PointCloud2 &  cloud)
protected

Extract a point cloud from laser scan points that meet criteria.

Definition at line 128 of file scan_finder.cpp.

◆ find()

bool robot_calibration::ScanFinder::find ( robot_calibration_msgs::CalibrationData *  msg)
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.

Parameters
msgThe message to which observations should be added.
Returns
True if feature finder succeeded in finding the features and adding them to the observation list. False otherwise.

Implements robot_calibration::FeatureFinder.

Definition at line 111 of file scan_finder.cpp.

◆ init()

bool robot_calibration::ScanFinder::init ( const std::string &  name,
ros::NodeHandle nh 
)
virtual

Initialize the feature finder.

Parameters
nameThe name of this finder.
nhThe nodehandle to use when loading feature finder configuration data.
Returns
True/False if the feature finder was able to be initialized

Reimplemented from robot_calibration::FeatureFinder.

Definition at line 41 of file scan_finder.cpp.

◆ scanCallback()

void robot_calibration::ScanFinder::scanCallback ( const sensor_msgs::LaserScan &  scan)
protectedvirtual

ROS callback - updates scan_ and resets waiting_ to false.

Definition at line 82 of file scan_finder.cpp.

◆ waitForScan()

bool robot_calibration::ScanFinder::waitForScan ( )
protectedvirtual

Wait until a new scan has arrived.

Definition at line 91 of file scan_finder.cpp.

Member Data Documentation

◆ laser_sensor_name_

std::string robot_calibration::ScanFinder::laser_sensor_name_
protected

Definition at line 74 of file scan_finder.h.

◆ max_x_

double robot_calibration::ScanFinder::max_x_
protected

Definition at line 76 of file scan_finder.h.

◆ max_y_

double robot_calibration::ScanFinder::max_y_
protected

Definition at line 78 of file scan_finder.h.

◆ min_x_

double robot_calibration::ScanFinder::min_x_
protected

Definition at line 75 of file scan_finder.h.

◆ min_y_

double robot_calibration::ScanFinder::min_y_
protected

Definition at line 77 of file scan_finder.h.

◆ output_debug_

bool robot_calibration::ScanFinder::output_debug_
protected

Definition at line 83 of file scan_finder.h.

◆ publisher_

ros::Publisher robot_calibration::ScanFinder::publisher_
protected

Definition at line 66 of file scan_finder.h.

◆ scan_

sensor_msgs::LaserScan robot_calibration::ScanFinder::scan_
protected

Definition at line 72 of file scan_finder.h.

◆ subscriber_

ros::Subscriber robot_calibration::ScanFinder::subscriber_
protected

Definition at line 65 of file scan_finder.h.

◆ tf_buffer_

tf2_ros::Buffer robot_calibration::ScanFinder::tf_buffer_
protected

Definition at line 68 of file scan_finder.h.

◆ tf_listener_

tf2_ros::TransformListener robot_calibration::ScanFinder::tf_listener_
protected

Definition at line 69 of file scan_finder.h.

◆ transform_frame_

std::string robot_calibration::ScanFinder::transform_frame_
protected

Definition at line 81 of file scan_finder.h.

◆ waiting_

bool robot_calibration::ScanFinder::waiting_
protected

Definition at line 71 of file scan_finder.h.

◆ z_offset_

double robot_calibration::ScanFinder::z_offset_
protected

Definition at line 80 of file scan_finder.h.

◆ z_repeats_

int robot_calibration::ScanFinder::z_repeats_
protected

Definition at line 79 of file scan_finder.h.


The documentation for this class was generated from the following files:


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