18 #ifndef ROBOT_CALIBRATION_CAPTURE_ROBOT_FINDER_H 19 #define ROBOT_CALIBRATION_CAPTURE_ROBOT_FINDER_H 33 virtual bool find(robot_calibration_msgs::CalibrationData * msg);
52 #endif // ROBOT_CALIBRATION_CAPTURE_ROBOT_FINDER_H
std::string robot_sensor_name_
ros::Publisher robot_publisher_
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 ~RobotFinder()=default
Calibration code lives under this namespace.
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Finds the largest plane in a point cloud.