Go to the documentation of this file.
18 #ifndef ROBOT_CALIBRATION_CAPTURE_SCAN_FINDER_H
19 #define ROBOT_CALIBRATION_CAPTURE_SCAN_FINDER_H
23 #include <robot_calibration_msgs/CalibrationData.h>
24 #include <sensor_msgs/LaserScan.h>
41 virtual bool find(robot_calibration_msgs::CalibrationData * msg);
47 virtual void scanCallback(
const sensor_msgs::LaserScan& scan);
63 robot_calibration_msgs::CalibrationData * msg);
88 #endif // ROBOT_CALIBRATION_CAPTURE_SCAN_FINDER_H
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....
virtual ~ScanFinder()=default
std::string laser_sensor_name_
Base class for a feature finder.
tf2_ros::Buffer tf_buffer_
The scan finder is useful for aligning a laser scanner with other sensors. In particular,...
sensor_msgs::LaserScan scan_
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
tf2_ros::TransformListener tf_listener_
ros::Publisher publisher_
void extractPoints(sensor_msgs::PointCloud2 &cloud)
Extract a point cloud from laser scan points that meet criteria.
virtual void scanCallback(const sensor_msgs::LaserScan &scan)
ROS callback - updates scan_ and resets waiting_ to false.
Calibration code lives under this namespace.
void extractObservation(const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg)
Extract the point cloud into a calibration message.
virtual bool waitForScan()
Wait until a new scan has arrived.
std::string transform_frame_
ros::Subscriber subscriber_
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01