Fawkes API
Fawkes Development Version
|
21 #ifndef LASER_CALIBRATION_H
22 #define LASER_CALIBRATION_H
24 #include <core/exception.h>
25 #include <interfaces/Laser360Interface.h>
26 #include <pcl/point_cloud.h>
27 #include <pcl/point_types.h>
32 typedef pcl::PointXYZ Point;
34 typedef PointCloud::Ptr PointCloudPtr;
39 class NetworkConfiguration;
49 return (deg * M_PI / 180.f);
72 std::string config_path);
84 float get_matching_cost(PointCloudPtr cloud1, PointCloudPtr cloud2,
float *rot_yaw);
PointCloudPtr laser_to_pointcloud(const LaserInterface &laser)
Convert the laser data into a pointcloud.
PointCloudPtr filter_left_cloud(PointCloudPtr input)
Remove all points that are left of the robot.
LaserCalibration(LaserInterface *laser, fawkes::tf::Transformer *tf_transformer, fawkes::NetworkConfiguration *config, std::string config_path)
Constructor.
LaserInterface * laser_
The laser that provides the input data.
Exception()
Constructor for subclasses.
PointCloudPtr filter_right_cloud(PointCloudPtr input)
Remove all points that are right of the robot.
static const uint max_iterations_
The number of iterations to run before aborting the calibration.
static const size_t min_points
The number of points required in a pointcloud to use it as input data.
fawkes::tf::Transformer * tf_transformer_
The transformer used to compute transforms.
virtual void calibrate()=0
The actual calibration procedure.
PointCloudPtr filter_out_ground(PointCloudPtr input)
Remove all points that belong to the ground.
const std::string config_path_
The config path to use for reading and updating config values.
InsufficientDataException(const char *error)
Constructor.
Abstract base class for laser calibration.
PointCloudPtr filter_cloud_in_rear(PointCloudPtr input)
Remove points in the rear of the robot.
void transform_pointcloud(const std::string &target_frame, PointCloudPtr cloud)
Transform the points in a pointcloud.
fawkes::NetworkConfiguration * config_
The network config to use for reading and updating config values.
PointCloudPtr filter_center_cloud(PointCloudPtr input)
Remove the center of a pointcloud This removes all points around the origin of the pointcloud.
float get_mean_z(PointCloudPtr cloud)
Compute the mean z value of all points in the given pointcloud.
Remote configuration via Fawkes net.
Fawkes library namespace.
virtual ~LaserCalibration()
Destructor.
float deg2rad(float deg)
Convert an angle given in degrees to radians.
static const long sleep_time_
Time in micro seconds to sleep between iterations.
Laser360Interface Fawkes BlackBoard Interface.
float get_matching_cost(PointCloudPtr cloud1, PointCloudPtr cloud2, float *rot_yaw)
Compare two pointclouds with ICP.
Exception that is thrown if there are not enough laser points to do a matching.
Base class for exceptions in Fawkes.