00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Redistribution and use in source and binary forms, with or without 00005 * modification, are permitted provided that the following conditions 00006 * are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above 00011 * copyright notice, this list of conditions and the following 00012 * disclaimer in the documentation and/or other materials provided 00013 * with the distribution. 00014 * * Neither the name of the Willow Garage nor the names of its 00015 * contributors may be used to endorse or promote products derived 00016 * from this software without specific prior written permission. 00017 * 00018 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00019 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00020 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00021 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00022 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00023 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00024 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00025 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00026 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00027 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00028 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00029 * POSSIBILITY OF SUCH DAMAGE. 00030 *********************************************************************/ 00031 00032 #include "camera_calibration_parsers/parse.h" 00033 #include "camera_calibration_parsers/parse_wrapper.h" 00034 00035 #include <boost/python.hpp> 00036 #include <ros/serialization.h> 00037 00038 namespace camera_calibration_parsers { 00039 00040 /* Write a ROS message into a serialized string. 00041 * @from https://github.com/galou/python_bindings_tutorial/blob/master/src/add_two_ints_wrapper.cpp#L27 00042 */ 00043 template <typename M> 00044 std::string to_python(const M& msg) 00045 { 00046 size_t serial_size = ros::serialization::serializationLength(msg); 00047 boost::shared_array<uint8_t> buffer(new uint8_t[serial_size]); 00048 ros::serialization::OStream stream(buffer.get(), serial_size); 00049 ros::serialization::serialize(stream, msg); 00050 std::string str_msg; 00051 str_msg.reserve(serial_size); 00052 for (size_t i = 0; i < serial_size; ++i) 00053 { 00054 str_msg.push_back(buffer[i]); 00055 } 00056 return str_msg; 00057 } 00058 00059 // Wrapper for readCalibration() 00060 boost::python::tuple readCalibrationWrapper(const std::string& file_name) 00061 { 00062 std::string camera_name; 00063 sensor_msgs::CameraInfo camera_info; 00064 bool result = readCalibration(file_name, camera_name, camera_info); 00065 std::string cam_info = to_python(camera_info); 00066 return boost::python::make_tuple(result, camera_name, cam_info); 00067 } 00068 00069 BOOST_PYTHON_MODULE(camera_calibration_parsers_wrapper) 00070 { 00071 boost::python::def("__readCalibrationWrapper", readCalibrationWrapper, boost::python::args("file_name"), ""); 00072 } 00073 00074 } //namespace camera_calibration_parsers