camera_calibration_parsers Namespace Reference

Functions

bool parseCalibration (const std::string &buffer, const std::string &format, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
 Parse calibration parameters from a string in memory.
bool parseCalibrationIni (const std::string &buffer, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
 Parse calibration parameters from a string in memory of INI format.
bool readCalibration (const std::string &file_name, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
 Read calibration parameters from a file.
bool readCalibrationIni (const std::string &file_name, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
 Read calibration parameters from an INI file.
bool readCalibrationIni (std::istream &in, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
 Read calibration parameters from an INI file.
bool readCalibrationYml (const std::string &file_name, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
 Read calibration parameters from a YAML file.
bool readCalibrationYml (std::istream &in, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
 Read calibration parameters from a YAML file.
bool writeCalibration (const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
 Write calibration parameters to a file.
bool writeCalibrationIni (const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
 Write calibration parameters to a file in INI format.
bool writeCalibrationIni (std::ostream &out, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
 Write calibration parameters to a file in INI format.
bool writeCalibrationYml (const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
 Write calibration parameters to a file in YAML format.
bool writeCalibrationYml (std::ostream &out, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
 Write calibration parameters to a file in YAML format.

Detailed Description

Todo:
: use stream-based API, so no read/parse distinction

Function Documentation

bool camera_calibration_parsers::parseCalibration ( const std::string &  buffer,
const std::string &  format,
std::string &  camera_name,
sensor_msgs::CameraInfo &  cam_info 
)

Parse calibration parameters from a string in memory.

Parameters:
buffer Calibration string
format Format of calibration string, "yml" or "ini"
[out] camera_name Name of the camera
[out] cam_info Camera parameters

Definition at line 28 of file parse.cpp.

bool camera_calibration_parsers::parseCalibrationIni ( const std::string &  buffer,
std::string &  camera_name,
sensor_msgs::CameraInfo &  cam_info 
)

Parse calibration parameters from a string in memory of INI format.

Parameters:
buffer Calibration string
[out] camera_name Name of the camera
[out] cam_info Camera parameters

Definition at line 177 of file parse_ini.cpp.

bool camera_calibration_parsers::readCalibration ( const std::string &  file_name,
std::string &  camera_name,
sensor_msgs::CameraInfo &  cam_info 
)

Read calibration parameters from a file.

The file may be YAML or INI format.

Parameters:
file_name File to read
[out] camera_name Name of the camera
[out] cam_info Camera parameters

Definition at line 17 of file parse.cpp.

bool camera_calibration_parsers::readCalibrationIni ( const std::string &  file_name,
std::string &  camera_name,
sensor_msgs::CameraInfo &  cam_info 
)

Read calibration parameters from an INI file.

Parameters:
file_name File to read
[out] camera_name Name of the camera
[out] cam_info Camera parameters

Definition at line 162 of file parse_ini.cpp.

bool camera_calibration_parsers::readCalibrationIni ( std::istream &  in,
std::string &  camera_name,
sensor_msgs::CameraInfo &  cam_info 
)

Read calibration parameters from an INI file.

Parameters:
in Input stream to read from
[out] camera_name Name of the camera
[out] cam_info Camera parameters

Definition at line 156 of file parse_ini.cpp.

bool camera_calibration_parsers::readCalibrationYml ( const std::string &  file_name,
std::string &  camera_name,
sensor_msgs::CameraInfo &  cam_info 
)

Read calibration parameters from a YAML file.

Parameters:
file_name File to read
[out] camera_name Name of the camera
[out] cam_info Camera parameters

Definition at line 152 of file parse_yml.cpp.

bool camera_calibration_parsers::readCalibrationYml ( std::istream &  in,
std::string &  camera_name,
sensor_msgs::CameraInfo &  cam_info 
)

Read calibration parameters from a YAML file.

Parameters:
in Input stream to read from
[out] camera_name Name of the camera
[out] cam_info Camera parameters

Definition at line 99 of file parse_yml.cpp.

bool camera_calibration_parsers::writeCalibration ( const std::string &  file_name,
const std::string &  camera_name,
const sensor_msgs::CameraInfo &  cam_info 
)

Write calibration parameters to a file.

The file name extension (.yml, .yaml, or .ini) determines the output format.

Parameters:
file_name File to write
camera_name Name of the camera
cam_info Camera parameters

Definition at line 6 of file parse.cpp.

bool camera_calibration_parsers::writeCalibrationIni ( const std::string &  file_name,
const std::string &  camera_name,
const sensor_msgs::CameraInfo &  cam_info 
)

Write calibration parameters to a file in INI format.

Parameters:
file_name File to write
camera_name Name of the camera
cam_info Camera parameters

Definition at line 63 of file parse_ini.cpp.

bool camera_calibration_parsers::writeCalibrationIni ( std::ostream &  out,
const std::string &  camera_name,
const sensor_msgs::CameraInfo &  cam_info 
)

Write calibration parameters to a file in INI format.

Parameters:
out Output stream to write to
camera_name Name of the camera
cam_info Camera parameters

Todo:
time?
Todo:
time?

Definition at line 34 of file parse_ini.cpp.

bool camera_calibration_parsers::writeCalibrationYml ( const std::string &  file_name,
const std::string &  camera_name,
const sensor_msgs::CameraInfo &  cam_info 
)

Write calibration parameters to a file in YAML format.

Parameters:
file_name File to write
camera_name Name of the camera
cam_info Camera parameters

Definition at line 92 of file parse_yml.cpp.

bool camera_calibration_parsers::writeCalibrationYml ( std::ostream &  out,
const std::string &  camera_name,
const sensor_msgs::CameraInfo &  cam_info 
)

Write calibration parameters to a file in YAML format.

Parameters:
out Output stream to write to
camera_name Name of the camera
cam_info Camera parameters

Definition at line 58 of file parse_yml.cpp.

 All Namespaces Files Functions


camera_calibration_parsers
Author(s): Patrick Mihelich
autogenerated on Fri Jan 11 10:03:13 2013