54 #include <visp/vpXmlParserCamera.h>
55 #include <visp/vpCameraParameters.h>
57 #include <boost/program_options/options_description.hpp>
58 #include <boost/program_options/variables_map.hpp>
59 #include <boost/program_options/parsers.hpp>
60 #include <boost/filesystem.hpp>
64 namespace po = boost::program_options;
65 namespace fs = boost::filesystem;
68 int main(
int argc,
const char ** argv)
71 po::options_description desc(
"Usage examples:\n"
72 " convert_cam_param_file -i input_cam_parameters.ini -c Dragonfly2-8mm-ccmop -w 640 -h 480\n"
73 " convert_cam_param_file -i input_cam_parameters.yml -c Dragonfly2-8mm-ccmop -w 640 -h 480\n"
74 " convert_cam_param_file -i input_cam_parameters.xml -c Dragonfly2-8mm-ccmop -w 640 -h 480\n"
75 " convert_cam_param_file -i input_cam_parameters.xml -o input_cam_parameters.yml -c Dragonfly2-8mm-ccmop -w 640 -h 480\n"
78 (
"help",
"produce help message")
79 (
"input,i", po::value<std::string>(),
"input file path")
80 (
"output,o", po::value<std::string>(),
"output file path")
81 (
"camera,c", po::value<std::string>(),
"camera name")
82 (
"width,w", po::value<unsigned int>(),
"camera width")
83 (
"height,h", po::value<unsigned int>(),
"camera height")
84 (
"distortion,d",
"Use distortion model")
85 (
"force-deleting,f",
"Force deleting output file if this exists")
89 po::store(po::parse_command_line(argc, argv, desc), vm);
92 if (vm.count(
"help")) {
93 std::cout << desc << std::endl;
97 if (!(vm.count(
"input") && vm.count(
"camera") && vm.count(
"width") && vm.count(
"height"))) {
98 std::cout <<
"Missing options" << std::endl;
99 std::cout << desc << std::endl;
103 const fs::path inPath = vm[
"input"].as<std::string>();
107 vpCameraParameters vispParam;
108 sensor_msgs::CameraInfo rosParam;
109 const unsigned int width = vm[
"width"].as<uint>();
110 const unsigned int height = vm[
"height"].as<uint>();
112 if (inPath.extension() == std::string(
".xml")){
114 if (vm.count(
"output")){
115 outPath = vm[
"output"].as<std::string>();
118 outPath.replace_extension(fs::path(
".ini"));
121 if (boost::filesystem::exists(outPath)){
122 if (vm.count(
"force-deleting")){
123 boost::filesystem::remove(outPath);
125 std::cout <<
"Output file " << outPath.string() <<
" already exists. Use -f to force deleting"<< std::endl;
130 vpCameraParameters::vpCameraParametersProjType projModel;
132 if (vm.count(
"distortion")){
133 projModel = vpCameraParameters::perspectiveProjWithDistortion;
135 projModel = vpCameraParameters::perspectiveProjWithoutDistortion;
138 if (
parser.parse(vispParam, inPath.string().c_str(), vm[
"camera"].as<std::string>().c_str(),
139 projModel, width, height)!=vpXmlParserCamera::SEQUENCE_OK){
140 std::cout <<
"Error parsing visp input file " << inPath.string() << std::endl;
147 std::cout <<
"Error writing ros output file " << outPath.string() << std::endl;
151 }
else if (inPath.extension() == std::string(
".ini") || inPath.extension() == std::string(
".yml")){
153 if (vm.count(
"output")){
154 outPath = vm[
"output"].as<std::string>();
157 outPath.replace_extension(fs::path(
".xml"));
160 if (boost::filesystem::exists(outPath)){
161 if (vm.count(
"force-deleting")){
162 boost::filesystem::remove(outPath);
164 std::cout <<
"Output file " << outPath.string() <<
" already exists. Use -f to force deleting"<< std::endl;
169 std::string cameraName = vm[
"camera"].as<std::string>();
172 std::cout <<
"Error parsing ros input file " << inPath.string() << std::endl;
178 if(
parser.save(vispParam, outPath.string().c_str(), cameraName, width, height)!=vpXmlParserCamera::SEQUENCE_OK){
179 std::cout <<
"Error writing visp output file " << outPath.string() << std::endl;
184 std::cout <<
"Unknown input file format" << std::endl;
188 std::cout <<
"Successfully created output file: " << outPath << std::endl;