00001 #ifndef PCL_MESSAGE_CAMERAINFO_H
00002 #define PCL_MESSAGE_CAMERAINFO_H
00003 #include <string>
00004 #include <vector>
00005 #include <ostream>
00006 #include <boost/array.hpp>
00007
00008
00009 #include "Header.h"
00010 #include "RegionOfInterest.h"
00011
00012 namespace sensor_msgs
00013 {
00014 template <class ContainerAllocator>
00015 struct CameraInfo_
00016 {
00017 typedef CameraInfo_<ContainerAllocator> Type;
00018
00019 CameraInfo_()
00020 : header()
00021 , height(0)
00022 , width(0)
00023 , roi()
00024 , D()
00025 , K()
00026 , R()
00027 , P()
00028 {
00029 D.assign(0.0);
00030 K.assign(0.0);
00031 R.assign(0.0);
00032 P.assign(0.0);
00033 }
00034
00035 CameraInfo_(const ContainerAllocator& _alloc)
00036 : header(_alloc)
00037 , height(0)
00038 , width(0)
00039 , roi(_alloc)
00040 , D()
00041 , K()
00042 , R()
00043 , P()
00044 {
00045 D.assign(0.0);
00046 K.assign(0.0);
00047 R.assign(0.0);
00048 P.assign(0.0);
00049 }
00050
00051 typedef ::roslib::Header_<ContainerAllocator> _header_type;
00052 ::roslib::Header_<ContainerAllocator> header;
00053
00054 typedef uint32_t _height_type;
00055 uint32_t height;
00056
00057 typedef uint32_t _width_type;
00058 uint32_t width;
00059
00060 typedef ::sensor_msgs::RegionOfInterest_<ContainerAllocator> _roi_type;
00061 ::sensor_msgs::RegionOfInterest_<ContainerAllocator> roi;
00062
00063 typedef boost::array<double, 5> _D_type;
00064 boost::array<double, 5> D;
00065
00066 typedef boost::array<double, 9> _K_type;
00067 boost::array<double, 9> K;
00068
00069 typedef boost::array<double, 9> _R_type;
00070 boost::array<double, 9> R;
00071
00072 typedef boost::array<double, 12> _P_type;
00073 boost::array<double, 12> P;
00074
00075 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo_<ContainerAllocator> > Ptr;
00076 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo_<ContainerAllocator> const> ConstPtr;
00077 };
00078 typedef ::sensor_msgs::CameraInfo_<std::allocator<void> > CameraInfo;
00079
00080 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo> CameraInfoPtr;
00081 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo const> CameraInfoConstPtr;
00082 }
00083
00084 #endif // PCL_MESSAGE_CAMERAINFO_H
00085