Classes | Typedefs | Enumerations | Functions | Variables
robot_calibration Namespace Reference

Calibration code lives under this namespace. More...

Classes

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...
 
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  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
 This class processes the point cloud input to find a checkerboard. 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...
 
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
 
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...
 

Typedefs

typedef std::map< std::string, FeatureFinderPtrFeatureFinderMap
 
typedef boost::shared_ptr< FeatureFinderFeatureFinderPtr
 

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)
 
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...
 
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
 

Detailed Description

Calibration code lives under this namespace.

Typedef Documentation

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.

Enumeration Type Documentation

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.

Function Documentation

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 261 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.

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.

Parameters
file_nameName of the bag file to load.
description_msgThis will be loaded with the URDF string.
dataThis 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 26 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 248 of file models.cpp.

sensor_msgs::CameraInfo robot_calibration::updateCameraInfo ( double  camera_fx,
double  camera_fy,
double  camera_cx,
double  camera_cy,
const sensor_msgs::CameraInfo &  info 
)
inline

Update the camera calibration with the new offsets.

Definition at line 54 of file camera_info.h.

Variable Documentation

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 30 of file checkerboard_finder.cpp.

const unsigned robot_calibration::Y = 1

Definition at line 31 of file checkerboard_finder.cpp.

const unsigned robot_calibration::Z = 2

Definition at line 32 of file checkerboard_finder.cpp.



robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30