Go to the documentation of this file.
18 #ifndef ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
19 #define ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
25 #include <robot_calibration_msgs/CalibrationData.h>
40 virtual bool find(robot_calibration_msgs::CalibrationData * msg);
46 virtual void cameraCallback(
const sensor_msgs::PointCloud2& cloud);
59 double min_x,
double max_x,
double min_y,
double max_y,
double min_z,
double max_z);
66 virtual sensor_msgs::PointCloud2
extractPlane(sensor_msgs::PointCloud2& cloud);
76 const sensor_msgs::PointCloud2& cloud,
77 robot_calibration_msgs::CalibrationData * msg,
114 #endif // ROBOT_CALIBRATION_CAPTURE_PLANE_FINDER_H
ros::Publisher publisher_
Finds the largest plane in a point cloud.
tf2_ros::TransformListener tf_listener_
Base class for a feature finder.
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Base class for a feature finder.
tf2_ros::Buffer tf_buffer_
virtual void removeInvalidPoints(sensor_msgs::PointCloud2 &cloud, double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)
Remove invalid points from a cloud.
virtual ~PlaneFinder()=default
DepthCameraInfoManager depth_camera_manager_
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....
double initial_sampling_distance_
ros::Subscriber subscriber_
Eigen::Vector3d desired_normal_
std::string plane_sensor_name_
virtual void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
ROS callback - updates cloud_ and resets waiting_ to false.
std::string transform_frame_
virtual bool waitForCloud()
Wait until a new cloud has arrived.
sensor_msgs::PointCloud2 cloud_
Calibration code lives under this namespace.
virtual void extractObservation(const std::string &sensor_name, const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg, ros::Publisher *publisher)
Extract points from a cloud into a calibration message.
virtual sensor_msgs::PointCloud2 extractPlane(sensor_msgs::PointCloud2 &cloud)
Extract a plane from the point cloud.
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01