Class ScanFinder
- Defined in File scan_finder.hpp 
Inheritance Relationships
Base Type
- public robot_calibration::FeatureFinder(Class FeatureFinder)
Class Documentation
- 
class ScanFinder : public robot_calibration::FeatureFinder
- 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. - Public Functions - 
ScanFinder()
 - 
virtual ~ScanFinder() = default
 - Initialize the feature finder. - Parameters:
- name – The name of this finder. 
- node – The node to use when loading feature finder configuration data. 
 
- Returns:
- True/False if the feature finder was able to be initialized 
 
 - 
virtual bool find(robot_calibration_msgs::msg::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. - Parameters:
- msg – The 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. 
 
 - Protected Functions - ROS callback - updates scan_ and resets waiting_ to false. 
 - 
virtual bool waitForScan()
- Wait until a new scan has arrived. 
 - 
void extractPoints(sensor_msgs::msg::PointCloud2 &cloud)
- Extract a point cloud from laser scan points that meet criteria. 
 - 
void extractObservation(const sensor_msgs::msg::PointCloud2 &cloud, robot_calibration_msgs::msg::CalibrationData *msg)
- Extract the point cloud into a calibration message. 
 - Protected Attributes - 
rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr subscriber_
 - 
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr publisher_
 - 
rclcpp::Clock::SharedPtr clock_
 - 
bool waiting_
 - 
sensor_msgs::msg::LaserScan scan_
 - 
std::string laser_sensor_name_
 - 
double min_x_
 - 
double max_x_
 - 
double min_y_
 - 
double max_y_
 - 
int z_repeats_
 - 
double z_offset_
 - 
std::string transform_frame_
 - 
bool output_debug_
 
- 
ScanFinder()