Program Listing for File scan_finder.hpp

Return to documentation for file (/tmp/ws/src/robot_calibration/robot_calibration/include/robot_calibration/finders/scan_finder.hpp)

/*
 * Copyright (C) 2022 Michael Ferguson
 * Copyright (C) 2014-2017 Fetch Robotics Inc.
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 *     http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 */

#ifndef ROBOT_CALIBRATION_FINDERS_SCAN_FINDER_HPP
#define ROBOT_CALIBRATION_FINDERS_SCAN_FINDER_HPP

#include <rclcpp/rclcpp.hpp>
#include <robot_calibration/finders/feature_finder.hpp>
#include <robot_calibration_msgs/msg/calibration_data.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>

namespace robot_calibration
{
class ScanFinder : public FeatureFinder
{
public:
  ScanFinder();
  virtual ~ScanFinder() = default;
  virtual bool init(const std::string& name,
                    std::shared_ptr<tf2_ros::Buffer> buffer,
                    rclcpp::Node::SharedPtr node);
  virtual bool find(robot_calibration_msgs::msg::CalibrationData * msg);

protected:
  virtual void scanCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr scan);

  virtual bool waitForScan();

  void extractPoints(sensor_msgs::msg::PointCloud2& cloud);

  void extractObservation(const sensor_msgs::msg::PointCloud2& cloud,
                          robot_calibration_msgs::msg::CalibrationData * msg);

  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_;
};

}  // namespace robot_calibration

#endif  // ROBOT_CALIBRATION_FINDERS_SCAN_FINDER_HPP