stereo_image.h
Go to the documentation of this file.
00001 /* +------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)            |
00003    |                          http://www.mrpt.org/                          |
00004    |                                                                        |
00005    | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file     |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                |
00007    | Released under BSD License. See details in http://www.mrpt.org/License |
00008    +------------------------------------------------------------------------+ */
00009 
00010 /*---------------------------------------------------------------
00011         APPLICATION: mrpt_ros bridge
00012         FILE: stereo_image.h
00013         AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
00014   ---------------------------------------------------------------*/
00015 
00016 #ifndef MRPT_BRIDGE_STEREO_IMAGE_H
00017 #define MRPT_BRIDGE_STEREO_IMAGE_H
00018 
00019 #include <cstring> // size_t
00020 #include <sensor_msgs/Image.h>
00021 #include <mrpt/obs/CObservationStereoImages.h>
00022 #include <stereo_msgs/DisparityImage.h>
00023 
00024 using namespace mrpt::obs;
00025 
00026 
00027 namespace mrpt_bridge
00028 {
00029     namespace stereo_image
00030     {
00031         bool mrpt2ros(const CObservationStereoImages &obj,const std_msgs::Header &msg_header,
00032                       sensor_msgs::Image &left, sensor_msgs::Image &right,
00033                       stereo_msgs::DisparityImage &disparity);
00034     }
00035 }
00036 
00037 
00038 #endif //MRPT_BRIDGE_STEREO_IMAGE_H


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06