$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions 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 copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00039 #include <karto_scan_matcher/karto_scan_matcher.h> 00040 #include <boost/python.hpp> 00041 #include <boost/python/suite/indexing/vector_indexing_suite.hpp> 00042 00043 namespace karto_scan_matcher 00044 { 00045 00046 namespace sm=sensor_msgs; 00047 namespace gm=geometry_msgs; 00048 00049 00050 BOOST_PYTHON_MODULE(karto_scan_matching) 00051 { 00052 using namespace boost::python; 00053 using sm::LaserScan; 00054 using gm::Pose2D; 00055 using boost::shared_ptr; 00056 using std_msgs::Header; 00057 using ros::Time; 00058 00059 class_<LaserScan, shared_ptr<LaserScan> >("LaserScanCpp", init<>()) 00060 .def_readwrite("header", &LaserScan::header) 00061 .def_readwrite("angle_min", &LaserScan::angle_min) 00062 .def_readwrite("angle_max", &LaserScan::angle_max) 00063 .def_readwrite("angle_increment", &LaserScan::angle_increment) 00064 .def_readwrite("range_min", &LaserScan::range_min) 00065 .def_readwrite("range_max", &LaserScan::range_max) 00066 .def_readwrite("ranges", &LaserScan::ranges) 00067 ; 00068 00069 class_<Pose2D>("Pose2DCpp", init<>()) 00070 .def_readwrite("x", &Pose2D::x) 00071 .def_readwrite("y", &Pose2D::y) 00072 .def_readwrite("theta", &Pose2D::theta) 00073 ; 00074 00075 class_<ScanMatchResult>("ScanMatchResultCpp", init<>()) 00076 .def_readonly("pose", &ScanMatchResult::pose) 00077 .def_readonly("response", &ScanMatchResult::response) 00078 ; 00079 00080 class_<ScanWithPose>("ScanWithPoseCpp", init<LaserScan, Pose2D>()); 00081 00082 class_<KartoScanMatcher>("KartoScanMatcherCpp", 00083 init<LaserScan, Pose2D, double, double>()) 00084 .def("scan_match", &KartoScanMatcher::scanMatch) 00085 ; 00086 00087 class_<Header>("Header", init<>()) 00088 .def_readwrite("seq", &Header::seq) 00089 .def_readwrite("stamp", &Header::stamp) 00090 .def_readwrite("frame_id", &Header::frame_id) 00091 ; 00092 00093 class_<Time>("Time", init<>()) 00094 .def_readwrite("sec", &Time::sec) 00095 .def_readwrite("nsec", &Time::nsec) 00096 ; 00097 00098 00099 } 00100 00101 } // namespace