Functions | |
BOOST_PYTHON_MODULE (camera_calibration_parsers_wrapper) | |
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. More... | |
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. More... | |
def | readCalibration (file_name) |
bool | readCalibration (const std::string &file_name, std::string &camera_name, sensor_msgs::CameraInfo &cam_info) |
Read calibration parameters from a file. More... | |
bool | readCalibrationIni (std::istream &in, std::string &camera_name, sensor_msgs::CameraInfo &cam_info) |
Read calibration parameters from an INI file. More... | |
bool | readCalibrationIni (const std::string &file_name, std::string &camera_name, sensor_msgs::CameraInfo &cam_info) |
Read calibration parameters from an INI file. More... | |
boost::python::tuple | readCalibrationWrapper (const std::string &file_name) |
bool | readCalibrationYml (std::istream &in, std::string &camera_name, sensor_msgs::CameraInfo &cam_info) |
Read calibration parameters from a YAML file. More... | |
bool | readCalibrationYml (const std::string &file_name, std::string &camera_name, sensor_msgs::CameraInfo &cam_info) |
Read calibration parameters from a YAML file. More... | |
template<typename M > | |
std::string | to_python (const M &msg) |
bool | writeCalibration (const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info) |
Write calibration parameters to a file. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
camera_calibration_parsers::BOOST_PYTHON_MODULE | ( | camera_calibration_parsers_wrapper | ) |
Definition at line 69 of file parse_wrapper.cpp.
bool camera_calibration_parsers::parseCalibration | ( | const std::string & | buffer, |
const std::string & | format, | ||
std::string & | camera_name, | ||
sensor_msgs::CameraInfo & | cam_info | ||
) |
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.
buffer | Calibration string | |
[out] | camera_name | Name of the camera |
[out] | cam_info | Camera parameters |
Definition at line 242 of file parse_ini.cpp.
def camera_calibration_parsers.readCalibration | ( | file_name | ) |
Read .ini or .yaml calibration file and return (camera name and cameraInfo message). @param file_name: camera calibration file name @type file_name: str @return: (camera name, cameraInfo message) or None on Error @rtype: tuple(str, sensor_msgs.msg.CameraInfo | None
Definition at line 4 of file __init__.py.
bool camera_calibration_parsers::readCalibration | ( | const std::string & | file_name, |
std::string & | camera_name, | ||
sensor_msgs::CameraInfo & | cam_info | ||
) |
bool camera_calibration_parsers::readCalibrationIni | ( | std::istream & | in, |
std::string & | camera_name, | ||
sensor_msgs::CameraInfo & | cam_info | ||
) |
Read calibration parameters from an INI file.
in | Input stream to read from | |
[out] | camera_name | Name of the camera |
[out] | cam_info | Camera parameters |
Definition at line 221 of file parse_ini.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.
file_name | File to read | |
[out] | camera_name | Name of the camera |
[out] | cam_info | Camera parameters |
Definition at line 227 of file parse_ini.cpp.
boost::python::tuple camera_calibration_parsers::readCalibrationWrapper | ( | const std::string & | file_name | ) |
Definition at line 60 of file parse_wrapper.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.
in | Input stream to read from | |
[out] | camera_name | Name of the camera |
[out] | cam_info | Camera parameters |
Definition at line 158 of file parse_yml.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.
file_name | File to read | |
[out] | camera_name | Name of the camera |
[out] | cam_info | Camera parameters |
Definition at line 226 of file parse_yml.cpp.
std::string camera_calibration_parsers::to_python | ( | const M & | msg | ) |
Definition at line 44 of file parse_wrapper.cpp.
bool camera_calibration_parsers::writeCalibration | ( | const std::string & | file_name, |
const std::string & | camera_name, | ||
const sensor_msgs::CameraInfo & | cam_info | ||
) |
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.
out | Output stream to write to |
camera_name | Name of the camera |
cam_info | Camera parameters |
Definition at line 81 of file parse_ini.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.
file_name | File to write |
camera_name | Name of the camera |
cam_info | Camera parameters |
Definition at line 113 of file parse_ini.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.
out | Output stream to write to |
camera_name | Name of the camera |
cam_info | Camera parameters |
Definition at line 107 of file parse_yml.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.
file_name | File to write |
camera_name | Name of the camera |
cam_info | Camera parameters |
Definition at line 141 of file parse_yml.cpp.