Calibration code lives under this namespace. More...
Classes | |
class | BaseCalibration |
Class for moving the base around and calibrating imu and odometry. More... | |
class | CalibrationOffsetParser |
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be calibrated, and and parses the actual adjustments from the free parameters. More... | |
class | Camera3dModel |
Model of a camera on a kinematic chain. More... | |
class | CaptureManager |
struct | Chain3dToChain3d |
Error block for computing the residual error between two 3d data sources. This can be used to calibrate 3d cameras to arms, or 3d cameras to other 3d cameras. More... | |
struct | Chain3dToMesh |
Error block for computing the fit between a set of projected points and a mesh (usually part of the robot body). Typically used to align sensor with the robot footprint. More... | |
struct | Chain3dToPlane |
Error block for computing the fit between a set of projected points and a plane (aX + bY + cZ + d = 0). Typically used to align sensor with the ground, but could be used to align with a flat robot base, etc. More... | |
class | ChainManager |
Manages moving joints to a new pose, determining when they are settled, and returning current joint_states. More... | |
class | ChainModel |
Model of a kinematic chain. This is the basic instance where we transform the world observations into the proper root frame. More... | |
class | CheckerboardFinder |
Finds checkerboards in images or point clouds. More... | |
class | DepthCameraInfoManager |
Base class for a feature finder. More... | |
class | FeatureFinder |
Base class for a feature finder. More... | |
class | FeatureFinderLoader |
Load feature finders, based on param server config. More... | |
class | LedFinder |
This class processes the point cloud input to find the LED. More... | |
class | MeshLoader |
struct | OptimizationParams |
Class to hold parameters for optimization. More... | |
class | Optimizer |
Class to do optimization. More... | |
struct | OutrageousError |
Error block to restrict the offsets generated by ceres-solver from becoming outrageously large. More... | |
class | PlaneFinder |
Finds the largest plane in a point cloud. More... | |
struct | PlaneToPlaneError |
Error block for computing the fit between two sets of projected points and their planar models plane (aX + bY + cZ + d = 0). Typically used to align multiple 3d cameras when they are not able to see high-resolution checkerboards, but can see a common plane (wall/floor/etc). More... | |
class | RobotFinder |
class | ScanFinder |
The scan finder is useful for aligning a laser scanner with other sensors. In particular, the laser scan be multiplied in the Z direction in order to create a plane for plane to plane calibration. More... | |
Typedefs | |
typedef std::map< std::string, FeatureFinderPtr > | FeatureFinderMap |
typedef boost::shared_ptr< FeatureFinder > | FeatureFinderPtr |
using | MeshPtr = std::shared_ptr< shapes::Mesh > |
Enumerations | |
enum | { CAMERA_INFO_P_FX_INDEX =0, CAMERA_INFO_P_FY_INDEX =5, CAMERA_INFO_P_CX_INDEX =2, CAMERA_INFO_P_CY_INDEX =6 } |
enum | { CAMERA_INFO_K_FX_INDEX =0, CAMERA_INFO_K_FY_INDEX =4, CAMERA_INFO_K_CX_INDEX =2, CAMERA_INFO_K_CY_INDEX =5 } |
enum | { CAMERA_INFO_D_1 =0, CAMERA_INFO_D_2 =1, CAMERA_INFO_D_3 =2, CAMERA_INFO_D_4 =3, CAMERA_INFO_D_5 =4 } |
enum | { CAMERA_PARAMS_CX_INDEX =0, CAMERA_PARAMS_CY_INDEX =1, CAMERA_PARAMS_FX_INDEX =2, CAMERA_PARAMS_FY_INDEX =3, CAMERA_PARAMS_Z_SCALE_INDEX =4, CAMERA_PARAMS_Z_OFFSET_INDEX =5 } |
Functions | |
void | axis_magnitude_from_rotation (const KDL::Rotation &r, double &x, double &y, double &z) |
Converts from KDL::Rotation to angle-axis-with-integrated-magnitude. More... | |
double | distancePoints (const geometry_msgs::Point p1, const geometry_msgs::Point p2) |
double | distToLine (Eigen::Vector3d &a, Eigen::Vector3d &b, Eigen::Vector3d c) |
Get the squared distance line segment A-B for point C. More... | |
bool | exportResults (Optimizer &optimizer, const std::string &initial_urdf, const std::vector< robot_calibration_msgs::CalibrationData > &data) |
Write the outputs of a calibration. More... | |
Eigen::Vector3d | getCentroid (Eigen::MatrixXd points) |
Get the centroid of a point cloud. More... | |
Eigen::MatrixXd | getMatrix (const std::vector< geometry_msgs::PointStamped > &points) |
Get an Eigen::MatrixXd from a vector of PointStamped. More... | |
bool | getPlane (Eigen::MatrixXd points, Eigen::Vector3d &normal, double &d) |
Find the plane parameters for a point cloud. More... | |
bool | getPosesFromBag (const std::string &pose_bag_name, std::vector< robot_calibration_msgs::CaptureConfig > &poses) |
Load a vector of calibration poses from a bagfile. More... | |
int | getSensorIndex (const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor) |
Determine which observation index corresponds to a particular sensor name. More... | |
bool | hasSensor (const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor) |
Determine if a sample of data has an observation from the desired sensor. More... | |
bool | load_bag (const std::string &file_name, std_msgs::String &description_msg, std::vector< robot_calibration_msgs::CalibrationData > &data) |
Load a bagfile of calibration data. More... | |
double | positionFromMsg (const std::string &name, const sensor_msgs::JointState &msg) |
KDL::Rotation | rotation_from_axis_magnitude (const double x, const double y, const double z) |
Converts our angle-axis-with-integrated-magnitude representation to a KDL::Rotation. More... | |
int | sampleCloud (const sensor_msgs::PointCloud2 &points, double sample_distance, size_t max_points, std::vector< geometry_msgs::PointStamped > &sampled_points) |
sensor_msgs::CameraInfo | updateCameraInfo (double camera_fx, double camera_fy, double camera_cx, double camera_cy, const sensor_msgs::CameraInfo &info) |
Update the camera calibration with the new offsets. More... | |
Variables | |
const unsigned | B = 2 |
const unsigned | G = 1 |
const unsigned | R = 0 |
const unsigned | X = 0 |
const unsigned | Y = 1 |
const unsigned | Z = 2 |
Calibration code lives under this namespace.
typedef std::map<std::string, FeatureFinderPtr > robot_calibration::FeatureFinderMap |
Definition at line 35 of file feature_finder_loader.h.
Definition at line 34 of file feature_finder_loader.h.
using robot_calibration::MeshPtr = typedef std::shared_ptr<shapes::Mesh> |
Definition at line 32 of file mesh_loader.h.
anonymous enum |
Enumerator | |
---|---|
CAMERA_INFO_P_FX_INDEX | |
CAMERA_INFO_P_FY_INDEX | |
CAMERA_INFO_P_CX_INDEX | |
CAMERA_INFO_P_CY_INDEX |
Definition at line 29 of file camera_info.h.
anonymous enum |
Enumerator | |
---|---|
CAMERA_INFO_K_FX_INDEX | |
CAMERA_INFO_K_FY_INDEX | |
CAMERA_INFO_K_CX_INDEX | |
CAMERA_INFO_K_CY_INDEX |
Definition at line 34 of file camera_info.h.
anonymous enum |
Enumerator | |
---|---|
CAMERA_INFO_D_1 | |
CAMERA_INFO_D_2 | |
CAMERA_INFO_D_3 | |
CAMERA_INFO_D_4 | |
CAMERA_INFO_D_5 |
Definition at line 39 of file camera_info.h.
anonymous enum |
Enumerator | |
---|---|
CAMERA_PARAMS_CX_INDEX | |
CAMERA_PARAMS_CY_INDEX | |
CAMERA_PARAMS_FX_INDEX | |
CAMERA_PARAMS_FY_INDEX | |
CAMERA_PARAMS_Z_SCALE_INDEX | |
CAMERA_PARAMS_Z_OFFSET_INDEX |
Definition at line 45 of file camera_info.h.
void robot_calibration::axis_magnitude_from_rotation | ( | const KDL::Rotation & | r, |
double & | x, | ||
double & | y, | ||
double & | z | ||
) |
Converts from KDL::Rotation to angle-axis-with-integrated-magnitude.
Definition at line 282 of file models.cpp.
double robot_calibration::distancePoints | ( | const geometry_msgs::Point | p1, |
const geometry_msgs::Point | p2 | ||
) |
Definition at line 39 of file led_finder.cpp.
double robot_calibration::distToLine | ( | Eigen::Vector3d & | a, |
Eigen::Vector3d & | b, | ||
Eigen::Vector3d | c | ||
) |
Get the squared distance line segment A-B for point C.
a | Point representing one end of the line segment |
b | Point representing the other end of the line segment |
c | Point to get distance to line segment |
Based on "Real Time Collision Detection", pg 130
Definition at line 44 of file chain3d_to_mesh_error.h.
bool robot_calibration::exportResults | ( | Optimizer & | optimizer, |
const std::string & | initial_urdf, | ||
const std::vector< robot_calibration_msgs::CalibrationData > & | data | ||
) |
Write the outputs of a calibration.
optimizer | The optimizer instance, where we get our offsets from |
initial_urdf | The initial URDF, to which offsets are added |
data | The raw calibration data, currently used only to get CameraInfo |
Definition at line 28 of file calibration_export.cpp.
|
inline |
Get the centroid of a point cloud.
Definition at line 50 of file eigen_geometry.h.
|
inline |
Get an Eigen::MatrixXd from a vector of PointStamped.
Definition at line 35 of file eigen_geometry.h.
|
inline |
Find the plane parameters for a point cloud.
points | Point cloud to determine plane parameters |
normal | The calculated normal, returned by reference |
d | The calculated d value in the plane equation |
The equation of the plane will be ax + by + cz + d = 0, where a, b, and c are the normal.
Definition at line 64 of file eigen_geometry.h.
bool robot_calibration::getPosesFromBag | ( | const std::string & | pose_bag_name, |
std::vector< robot_calibration_msgs::CaptureConfig > & | poses | ||
) |
Load a vector of calibration poses from a bagfile.
Definition at line 32 of file capture_poses.cpp.
int robot_calibration::getSensorIndex | ( | const robot_calibration_msgs::CalibrationData & | msg, |
const std::string & | sensor | ||
) |
Determine which observation index corresponds to a particular sensor name.
Definition at line 30 of file calibration_data_helpers.h.
bool robot_calibration::hasSensor | ( | const robot_calibration_msgs::CalibrationData & | msg, |
const std::string & | sensor | ||
) |
Determine if a sample of data has an observation from the desired sensor.
Definition at line 47 of file calibration_data_helpers.h.
bool robot_calibration::load_bag | ( | const std::string & | file_name, |
std_msgs::String & | description_msg, | ||
std::vector< robot_calibration_msgs::CalibrationData > & | data | ||
) |
Load a bagfile of calibration data.
file_name | Name of the bag file to load. |
description_msg | This will be loaded with the URDF string. |
data | This will be loaded with the calibration data. |
Definition at line 42 of file load_bag.h.
double robot_calibration::positionFromMsg | ( | const std::string & | name, |
const sensor_msgs::JointState & | msg | ||
) |
Definition at line 27 of file models.cpp.
KDL::Rotation robot_calibration::rotation_from_axis_magnitude | ( | const double | x, |
const double | y, | ||
const double | z | ||
) |
Converts our angle-axis-with-integrated-magnitude representation to a KDL::Rotation.
Definition at line 269 of file models.cpp.
int robot_calibration::sampleCloud | ( | const sensor_msgs::PointCloud2 & | points, |
double | sample_distance, | ||
size_t | max_points, | ||
std::vector< geometry_msgs::PointStamped > & | sampled_points | ||
) |
Definition at line 40 of file plane_finder.cpp.
|
inline |
Update the camera calibration with the new offsets.
Definition at line 54 of file camera_info.h.
const unsigned robot_calibration::B = 2 |
Definition at line 37 of file led_finder.cpp.
const unsigned robot_calibration::G = 1 |
Definition at line 36 of file led_finder.cpp.
const unsigned robot_calibration::R = 0 |
Definition at line 35 of file led_finder.cpp.
const unsigned robot_calibration::X = 0 |
Definition at line 32 of file checkerboard_finder.cpp.
const unsigned robot_calibration::Y = 1 |
Definition at line 33 of file checkerboard_finder.cpp.
const unsigned robot_calibration::Z = 2 |
Definition at line 34 of file checkerboard_finder.cpp.