Classes | |
class | Exception |
class | IvtCalibration |
class | IvtImage |
Image message class that is interoperable with sensor_msgs/Image but uses a CByteImage representation for the image data. More... | |
class | IvtStereoCalibration |
Typedefs | |
typedef boost::shared_ptr < IvtImage const > | IvtImageConstPtr |
typedef boost::shared_ptr < IvtImage > | IvtImagePtr |
Functions | |
boost::shared_ptr< CCalibration > | calibrationImpl (const image_geometry::PinholeCameraModel &cam_model, bool forRectifiedImages) |
int | getCvType (const std::string &encoding) |
Convert a IvtImage to another encoding. | |
CByteImage::ImageType | getIvtType (const std::string &encoding) |
Get the CByteImage type enum corresponding to the encoding. | |
cv::Mat_< double > | matx33ToMat_ (const cv::Matx< double, 3, 3 > &matx) |
cv::Mat_< double > | matx34ToMat_ (const cv::Matx< double, 3, 4 > &matx) |
cv::Mat_< double > | matx35ToMat_ (const cv::Matx< double, 3, 5 > &matx) |
IvtImagePtr | toIvtCopy (const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string()) |
Convert a sensor_msgs::Image message to an Ivt-compatible CByteImage, copying the image data. | |
IvtImagePtr | toIvtCopy (const sensor_msgs::Image &source, const std::string &encoding=std::string()) |
Convert a sensor_msgs::Image message to an Ivt-compatible CByteImage, copying the image data. | |
IvtImageConstPtr | toIvtShare (const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string()) |
Convert an immutable sensor_msgs::Image message to an Ivt-compatible CByteImage, sharing the image data if possible. | |
IvtImageConstPtr | toIvtShare (const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string()) |
Convert an immutable sensor_msgs::Image message to an Ivt-compatible CByteImage, sharing the image data if possible. |
Copyright (c) 2016, Hutmacher Robin, Kleinert Daniel, Meißner Pascal All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
typedef boost::shared_ptr<IvtImage const> ivt_bridge::IvtImageConstPtr |
Definition at line 38 of file ivt_image.h.
typedef boost::shared_ptr<IvtImage> ivt_bridge::IvtImagePtr |
Definition at line 35 of file ivt_image.h.
boost::shared_ptr<CCalibration> ivt_bridge::calibrationImpl | ( | const image_geometry::PinholeCameraModel & | cam_model, |
bool | forRectifiedImages | ||
) |
Definition at line 56 of file ivt_calibration.cpp.
int ivt_bridge::getCvType | ( | const std::string & | encoding | ) |
Convert a IvtImage to another encoding.
Get the OpenCV type enum corresponding to the encoding.
For example, "bgr8" -> CV_8UC3.
Definition at line 28 of file ivt_image.cpp.
CByteImage::ImageType ivt_bridge::getIvtType | ( | const std::string & | encoding | ) |
Get the CByteImage type enum corresponding to the encoding.
For example, rgb8 -> eRGB24.
Definition at line 76 of file ivt_image.cpp.
cv::Mat_<double> ivt_bridge::matx33ToMat_ | ( | const cv::Matx< double, 3, 3 > & | matx | ) |
Definition at line 35 of file ivt_calibration.cpp.
cv::Mat_<double> ivt_bridge::matx34ToMat_ | ( | const cv::Matx< double, 3, 4 > & | matx | ) |
Definition at line 25 of file ivt_calibration.cpp.
cv::Mat_<double> ivt_bridge::matx35ToMat_ | ( | const cv::Matx< double, 3, 5 > & | matx | ) |
Definition at line 45 of file ivt_calibration.cpp.
IvtImagePtr ivt_bridge::toIvtCopy | ( | const sensor_msgs::ImageConstPtr & | source, |
const std::string & | encoding = std::string() |
||
) |
Convert a sensor_msgs::Image message to an Ivt-compatible CByteImage, copying the image data.
source | A shared_ptr to a sensor_msgs::Image message |
encoding | The desired encoding of the image data, one of the following strings:
|
If encoding is the empty string (the default), the returned IvtImage has the same encoding as source.
Definition at line 203 of file ivt_image.cpp.
IvtImagePtr ivt_bridge::toIvtCopy | ( | const sensor_msgs::Image & | source, |
const std::string & | encoding = std::string() |
||
) |
Convert a sensor_msgs::Image message to an Ivt-compatible CByteImage, copying the image data.
source | A sensor_msgs::Image message |
encoding | The desired encoding of the image data, one of the following strings:
|
If encoding is the empty string (the default), the returned IvtImage has the same encoding as source.
Definition at line 207 of file ivt_image.cpp.
IvtImageConstPtr ivt_bridge::toIvtShare | ( | const sensor_msgs::ImageConstPtr & | source, |
const std::string & | encoding = std::string() |
||
) |
Convert an immutable sensor_msgs::Image message to an Ivt-compatible CByteImage, sharing the image data if possible.
If the source encoding and desired encoding are the same, the returned IvtImage will share the image data with source without copying it. The returned IvtImage cannot be modified, as that could modify the source data.
source | A shared_ptr to a sensor_msgs::Image message |
encoding | The desired encoding of the image data, one of the following strings:
|
Definition at line 217 of file ivt_image.cpp.
IvtImageConstPtr ivt_bridge::toIvtShare | ( | const sensor_msgs::Image & | source, |
const boost::shared_ptr< void const > & | tracked_object, | ||
const std::string & | encoding = std::string() |
||
) |
Convert an immutable sensor_msgs::Image message to an Ivt-compatible CByteImage, sharing the image data if possible.
If the source encoding and desired encoding are the same, the returned IvtImage will share the image data with source without copying it. The returned IvtImage cannot be modified, as that could modify the source data.
This overload is useful when you have a shared_ptr to a message that contains a sensor_msgs::Image, and wish to share ownership with the containing message.
source | The sensor_msgs::Image message |
tracked_object | A shared_ptr to an object owning the sensor_msgs::Image |
encoding | The desired encoding of the image data, one of the following strings:
|
Definition at line 221 of file ivt_image.cpp.