|
Fawkes API
Fawkes Development Version
|
Abstract base class for laser calibration. More...
#include "laser_calibration.h"

Public Member Functions | |
| LaserCalibration (LaserInterface *laser, fawkes::tf::Transformer *tf_transformer, fawkes::NetworkConfiguration *config, std::string config_path) | |
| Constructor. More... | |
| virtual | ~LaserCalibration () |
| Destructor. More... | |
| virtual void | calibrate ()=0 |
| The actual calibration procedure. More... | |
Protected Member Functions | |
| PointCloudPtr | laser_to_pointcloud (const LaserInterface &laser) |
| Convert the laser data into a pointcloud. More... | |
| void | transform_pointcloud (const std::string &target_frame, PointCloudPtr cloud) |
| Transform the points in a pointcloud. More... | |
| PointCloudPtr | filter_cloud_in_rear (PointCloudPtr input) |
| Remove points in the rear of the robot. More... | |
| float | get_mean_z (PointCloudPtr cloud) |
| Compute the mean z value of all points in the given pointcloud. More... | |
| PointCloudPtr | filter_left_cloud (PointCloudPtr input) |
| Remove all points that are left of the robot. More... | |
| PointCloudPtr | filter_right_cloud (PointCloudPtr input) |
| Remove all points that are right of the robot. More... | |
| PointCloudPtr | filter_out_ground (PointCloudPtr input) |
| Remove all points that belong to the ground. More... | |
| float | get_matching_cost (PointCloudPtr cloud1, PointCloudPtr cloud2, float *rot_yaw) |
| Compare two pointclouds with ICP. More... | |
| PointCloudPtr | filter_center_cloud (PointCloudPtr input) |
| Remove the center of a pointcloud This removes all points around the origin of the pointcloud. More... | |
Protected Attributes | |
| LaserInterface * | laser_ |
| The laser that provides the input data. More... | |
| fawkes::tf::Transformer * | tf_transformer_ |
| The transformer used to compute transforms. More... | |
| fawkes::NetworkConfiguration * | config_ |
| The network config to use for reading and updating config values. More... | |
| const std::string | config_path_ |
| The config path to use for reading and updating config values. More... | |
Static Protected Attributes | |
| static const long | sleep_time_ = 50000 |
| Time in micro seconds to sleep between iterations. More... | |
| static const uint | max_iterations_ = 100 |
| The number of iterations to run before aborting the calibration. More... | |
| static const size_t | min_points = 10 |
| The number of points required in a pointcloud to use it as input data. More... | |
Abstract base class for laser calibration.
The class provides functions that are common for all calibration methods.
Definition at line 66 of file laser_calibration.h.
| LaserCalibration::LaserCalibration | ( | LaserInterface * | laser, |
| fawkes::tf::Transformer * | tf_transformer, | ||
| fawkes::NetworkConfiguration * | config, | ||
| std::string | config_path | ||
| ) |
Constructor.
| laser | The laser interface to fetch data from |
| tf_transformer | The transformer to use to compute transforms |
| config | The network config to read from and write updates to |
| config_path | The config path to read from and write updates to |
Definition at line 52 of file laser_calibration.cpp.
|
virtual |
Destructor.
Definition at line 61 of file laser_calibration.cpp.
|
pure virtual |
The actual calibration procedure.
Virtual function that is called once to calibrate the laser.
Implemented in YawCalibration, TimeOffsetCalibration, RollCalibration, and PitchCalibration.
|
protected |
Remove the center of a pointcloud This removes all points around the origin of the pointcloud.
Use this to remove the robot from the data.
| input | The pointcloud to filter |
Definition at line 236 of file laser_calibration.cpp.
Referenced by YawCalibration::get_current_cost().
|
protected |
Remove points in the rear of the robot.
| input | The pointcloud to remove the points from. |
Definition at line 113 of file laser_calibration.cpp.
Referenced by PitchCalibration::calibrate(), and RollCalibration::get_lr_mean_diff().
|
protected |
Remove all points that are left of the robot.
| input | The cloud to remove the points from |
Definition at line 153 of file laser_calibration.cpp.
Referenced by RollCalibration::get_lr_mean_diff().
|
protected |
Remove all points that belong to the ground.
Points that have a height < 0.1 are assumed to be part of the ground.
| input | The pointcloud to remove the points form |
Definition at line 186 of file laser_calibration.cpp.
|
protected |
Remove all points that are right of the robot.
| input | The cloud to remove the points from |
Definition at line 169 of file laser_calibration.cpp.
Referenced by RollCalibration::get_lr_mean_diff().
|
protected |
Compare two pointclouds with ICP.
Compute the best angle to rotate cloud2 into cloud1 with ICP and get the cost.
| cloud1 | The first input cloud, used as target cloud in ICP |
| cloud2 | The second input cloud, this is used as ICP input |
| rot_yaw | A pointer to a float to write the resulting rotation to |
Definition at line 206 of file laser_calibration.cpp.
References min_points.
Referenced by TimeOffsetCalibration::calibrate(), and YawCalibration::get_current_cost().
|
protected |
Compute the mean z value of all points in the given pointcloud.
This can be used to compute the height of a line, e.g., a line that should be on the ground. The value can be used to tweak the roll or pitch of the lasers.
| cloud | The cloud that is used to compute the mean z |
Definition at line 132 of file laser_calibration.cpp.
References min_points.
Referenced by PitchCalibration::calibrate(), and RollCalibration::get_lr_mean_diff().
|
protected |
Convert the laser data into a pointcloud.
The frame of the pointcloud is set to the frame of the laser, no transform is applied.
| laser | The laser interface to read the data from |
Definition at line 72 of file laser_calibration.cpp.
References fawkes::deg2rad(), fawkes::Laser360Interface::distances(), fawkes::Laser360Interface::frame(), and fawkes::Laser360Interface::maxlenof_distances().
Referenced by PitchCalibration::calibrate(), YawCalibration::get_current_cost(), TimeOffsetCalibration::get_lasercloud(), and RollCalibration::get_lr_mean_diff().
|
protected |
Transform the points in a pointcloud.
The pointcloud is transformed in-place, i.e., the referenced input pointcloud is updated to be in the target frame.
| target_frame | The frame all points should be transformed into |
| cloud | A reference to the pointcloud to transform |
Definition at line 94 of file laser_calibration.cpp.
References tf_transformer_, and fawkes::tf::Transformer::transform_point().
Referenced by PitchCalibration::calibrate(), YawCalibration::get_current_cost(), TimeOffsetCalibration::get_lasercloud(), and RollCalibration::get_lr_mean_diff().
|
protected |
The network config to use for reading and updating config values.
Definition at line 93 of file laser_calibration.h.
Referenced by PitchCalibration::calibrate(), RollCalibration::calibrate(), TimeOffsetCalibration::calibrate(), and YawCalibration::calibrate().
|
protected |
The config path to use for reading and updating config values.
Definition at line 95 of file laser_calibration.h.
Referenced by PitchCalibration::calibrate(), RollCalibration::calibrate(), TimeOffsetCalibration::calibrate(), and YawCalibration::calibrate().
|
protected |
The laser that provides the input data.
Definition at line 89 of file laser_calibration.h.
Referenced by PitchCalibration::calibrate(), TimeOffsetCalibration::calibrate(), YawCalibration::get_current_cost(), and RollCalibration::get_lr_mean_diff().
|
staticprotected |
The number of iterations to run before aborting the calibration.
Definition at line 99 of file laser_calibration.h.
Referenced by RollCalibration::calibrate(), and YawCalibration::calibrate().
|
staticprotected |
The number of points required in a pointcloud to use it as input data.
Definition at line 101 of file laser_calibration.h.
Referenced by RollCalibration::get_lr_mean_diff(), get_matching_cost(), and get_mean_z().
|
staticprotected |
Time in micro seconds to sleep between iterations.
Definition at line 97 of file laser_calibration.h.
Referenced by PitchCalibration::calibrate(), RollCalibration::calibrate(), and YawCalibration::calibrate().
|
protected |
The transformer used to compute transforms.
Definition at line 91 of file laser_calibration.h.
Referenced by transform_pointcloud().