module.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include "module.hpp"
36 
37 PyObject *mod_opencv;
38 
39 bp::object
40 cvtColor2Wrap(bp::object obj_in, const std::string & encoding_in, const std::string & encoding_out) {
41  // Convert the Python input to an image
42  cv::Mat mat_in;
43  convert_to_CvMat2(obj_in.ptr(), mat_in);
44 
45  // Call cv_bridge for color conversion
46  cv_bridge::CvImagePtr cv_image(new cv_bridge::CvImage(std_msgs::Header(), encoding_in, mat_in));
47 
48  cv::Mat mat = cv_bridge::cvtColor(cv_image, encoding_out)->image;
49 
50  return bp::object(boost::python::handle<>(pyopencv_from(mat)));
51 }
52 
53 bp::object
54 cvtColorForDisplayWrap(bp::object obj_in,
55  const std::string & encoding_in,
56  const std::string & encoding_out,
57  bool do_dynamic_scaling = false,
58  double min_image_value = 0.0,
59  double max_image_value = 0.0) {
60  // Convert the Python input to an image
61  cv::Mat mat_in;
62  convert_to_CvMat2(obj_in.ptr(), mat_in);
63 
64  cv_bridge::CvImagePtr cv_image(new cv_bridge::CvImage(std_msgs::Header(), encoding_in, mat_in));
65 
67  options.do_dynamic_scaling = do_dynamic_scaling;
68  options.min_image_value = min_image_value;
69  options.max_image_value = max_image_value;
70  cv::Mat mat = cv_bridge::cvtColorForDisplay(/*source=*/cv_image,
71  /*encoding_out=*/encoding_out,
72  /*options=*/options)->image;
73 
74  return bp::object(boost::python::handle<>(pyopencv_from(mat)));
75 }
76 
77 BOOST_PYTHON_FUNCTION_OVERLOADS(cvtColorForDisplayWrap_overloads, cvtColorForDisplayWrap, 3, 6)
78 
79 int CV_MAT_CNWrap(int i) {
80  return CV_MAT_CN(i);
81 }
82 
83 int CV_MAT_DEPTHWrap(int i) {
84  return CV_MAT_DEPTH(i);
85 }
86 
87 BOOST_PYTHON_MODULE(cv_bridge_boost)
88 {
89  do_numpy_import();
90  mod_opencv = PyImport_ImportModule("cv2");
91 
92  // Wrap the function to get encodings as OpenCV types
93  boost::python::def("getCvType", cv_bridge::getCvType);
94  boost::python::def("cvtColor2", cvtColor2Wrap);
95  boost::python::def("CV_MAT_CNWrap", CV_MAT_CNWrap);
96  boost::python::def("CV_MAT_DEPTHWrap", CV_MAT_DEPTHWrap);
97  boost::python::def("cvtColorForDisplay", cvtColorForDisplayWrap,
98  cvtColorForDisplayWrap_overloads(
99  boost::python::args("source", "encoding_in", "encoding_out", "do_dynamic_scaling",
100  "min_image_value", "max_image_value"),
101  "Convert image to display with specified encodings.\n\n"
102  "Args:\n"
103  " - source (numpy.ndarray): input image\n"
104  " - encoding_in (str): input image encoding\n"
105  " - encoding_out (str): encoding to which the image conveted\n"
106  " - do_dynamic_scaling (bool): flag to do dynamic scaling with min/max value\n"
107  " - min_image_value (float): minimum pixel value for dynamic scaling\n"
108  " - max_image_value (float): maximum pixel value for dynamic scaling\n"
109  ));
110 }
bp::object cvtColor2Wrap(bp::object obj_in, const std::string &encoding_in, const std::string &encoding_out)
Definition: module.cpp:40
PyObject * mod_opencv
Definition: module.cpp:37
int convert_to_CvMat2(const PyObject *o, cv::Mat &m)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
Convert a CvImage to another encoding using the same rules as toCvCopy.
Definition: cv_bridge.cpp:429
BOOST_PYTHON_MODULE(cv_bridge_boost)
Definition: module.cpp:87
PyObject * pyopencv_from(const Mat &m)
Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat r...
Definition: cv_bridge.h:76
bp::object cvtColorForDisplayWrap(bp::object obj_in, const std::string &encoding_in, const std::string &encoding_out, bool do_dynamic_scaling=false, double min_image_value=0.0, double max_image_value=0.0)
Definition: module.cpp:54
int CV_MAT_CNWrap(int i)
Definition: module.cpp:79
int getCvType(const std::string &encoding)
Get the OpenCV type enum corresponding to the encoding.
Definition: cv_bridge.cpp:72
CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr &source, const std::string &encoding=std::string(), const CvtColorForDisplayOptions options=CvtColorForDisplayOptions())
Converts an immutable sensor_msgs::Image message to another CvImage for display purposes, using practical conversion rules if needed.
Definition: cv_bridge.cpp:538
int CV_MAT_DEPTHWrap(int i)
Definition: module.cpp:83


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Thu Dec 12 2019 03:52:01