00001
00002 #ifndef SBA_MESSAGE_FRAME_H
00003 #define SBA_MESSAGE_FRAME_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014 #include "sba/CameraNode.h"
00015 #include "sba/WorldPoint.h"
00016 #include "sba/Projection.h"
00017
00018 namespace sba
00019 {
00020 template <class ContainerAllocator>
00021 struct Frame_ : public ros::Message
00022 {
00023 typedef Frame_<ContainerAllocator> Type;
00024
00025 Frame_()
00026 : header()
00027 , nodes()
00028 , points()
00029 , projections()
00030 {
00031 }
00032
00033 Frame_(const ContainerAllocator& _alloc)
00034 : header(_alloc)
00035 , nodes(_alloc)
00036 , points(_alloc)
00037 , projections(_alloc)
00038 {
00039 }
00040
00041 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00042 ::std_msgs::Header_<ContainerAllocator> header;
00043
00044 typedef std::vector< ::sba::CameraNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::CameraNode_<ContainerAllocator> >::other > _nodes_type;
00045 std::vector< ::sba::CameraNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::CameraNode_<ContainerAllocator> >::other > nodes;
00046
00047 typedef std::vector< ::sba::WorldPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::WorldPoint_<ContainerAllocator> >::other > _points_type;
00048 std::vector< ::sba::WorldPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::WorldPoint_<ContainerAllocator> >::other > points;
00049
00050 typedef std::vector< ::sba::Projection_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::Projection_<ContainerAllocator> >::other > _projections_type;
00051 std::vector< ::sba::Projection_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::Projection_<ContainerAllocator> >::other > projections;
00052
00053
00054 ROS_DEPRECATED uint32_t get_nodes_size() const { return (uint32_t)nodes.size(); }
00055 ROS_DEPRECATED void set_nodes_size(uint32_t size) { nodes.resize((size_t)size); }
00056 ROS_DEPRECATED void get_nodes_vec(std::vector< ::sba::CameraNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::CameraNode_<ContainerAllocator> >::other > & vec) const { vec = this->nodes; }
00057 ROS_DEPRECATED void set_nodes_vec(const std::vector< ::sba::CameraNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::CameraNode_<ContainerAllocator> >::other > & vec) { this->nodes = vec; }
00058 ROS_DEPRECATED uint32_t get_points_size() const { return (uint32_t)points.size(); }
00059 ROS_DEPRECATED void set_points_size(uint32_t size) { points.resize((size_t)size); }
00060 ROS_DEPRECATED void get_points_vec(std::vector< ::sba::WorldPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::WorldPoint_<ContainerAllocator> >::other > & vec) const { vec = this->points; }
00061 ROS_DEPRECATED void set_points_vec(const std::vector< ::sba::WorldPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::WorldPoint_<ContainerAllocator> >::other > & vec) { this->points = vec; }
00062 ROS_DEPRECATED uint32_t get_projections_size() const { return (uint32_t)projections.size(); }
00063 ROS_DEPRECATED void set_projections_size(uint32_t size) { projections.resize((size_t)size); }
00064 ROS_DEPRECATED void get_projections_vec(std::vector< ::sba::Projection_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::Projection_<ContainerAllocator> >::other > & vec) const { vec = this->projections; }
00065 ROS_DEPRECATED void set_projections_vec(const std::vector< ::sba::Projection_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sba::Projection_<ContainerAllocator> >::other > & vec) { this->projections = vec; }
00066 private:
00067 static const char* __s_getDataType_() { return "sba/Frame"; }
00068 public:
00069 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00070
00071 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00072
00073 private:
00074 static const char* __s_getMD5Sum_() { return "418ca143f82258a762de2cff21411737"; }
00075 public:
00076 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00077
00078 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00079
00080 private:
00081 static const char* __s_getMessageDefinition_() { return "# New Frame\n\
00082 Header header\n\
00083 \n\
00084 # New nodes (generally just 1, but want to leave this open)\n\
00085 CameraNode[] nodes\n\
00086 \n\
00087 # New points added from the frame\n\
00088 WorldPoint[] points\n\
00089 \n\
00090 # New projections\n\
00091 Projection[] projections\n\
00092 \n\
00093 ================================================================================\n\
00094 MSG: std_msgs/Header\n\
00095 # Standard metadata for higher-level stamped data types.\n\
00096 # This is generally used to communicate timestamped data \n\
00097 # in a particular coordinate frame.\n\
00098 # \n\
00099 # sequence ID: consecutively increasing ID \n\
00100 uint32 seq\n\
00101 #Two-integer timestamp that is expressed as:\n\
00102 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00103 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00104 # time-handling sugar is provided by the client library\n\
00105 time stamp\n\
00106 #Frame this data is associated with\n\
00107 # 0: no frame\n\
00108 # 1: global frame\n\
00109 string frame_id\n\
00110 \n\
00111 ================================================================================\n\
00112 MSG: sba/CameraNode\n\
00113 # Node Parameters\n\
00114 uint32 index\n\
00115 \n\
00116 # Contains a translation and rotation\n\
00117 geometry_msgs/Transform transform\n\
00118 \n\
00119 # Camera parameters from the K matrix\n\
00120 float64 fx\n\
00121 float64 fy\n\
00122 float64 cx\n\
00123 float64 cy\n\
00124 \n\
00125 # Only relevant for a stereo camera\n\
00126 float64 baseline\n\
00127 \n\
00128 # Whether the camera is fixed in space: i.e., its position is known\n\
00129 bool fixed\n\
00130 \n\
00131 ================================================================================\n\
00132 MSG: geometry_msgs/Transform\n\
00133 # This represents the transform between two coordinate frames in free space.\n\
00134 \n\
00135 Vector3 translation\n\
00136 Quaternion rotation\n\
00137 \n\
00138 ================================================================================\n\
00139 MSG: geometry_msgs/Vector3\n\
00140 # This represents a vector in free space. \n\
00141 \n\
00142 float64 x\n\
00143 float64 y\n\
00144 float64 z\n\
00145 ================================================================================\n\
00146 MSG: geometry_msgs/Quaternion\n\
00147 # This represents an orientation in free space in quaternion form.\n\
00148 \n\
00149 float64 x\n\
00150 float64 y\n\
00151 float64 z\n\
00152 float64 w\n\
00153 \n\
00154 ================================================================================\n\
00155 MSG: sba/WorldPoint\n\
00156 # World Point parameters\n\
00157 \n\
00158 # Point index\n\
00159 uint32 index\n\
00160 \n\
00161 # Coordinates in the world frame\n\
00162 float64 x\n\
00163 float64 y\n\
00164 float64 z\n\
00165 float64 w\n\
00166 \n\
00167 ================================================================================\n\
00168 MSG: sba/Projection\n\
00169 # Projection\n\
00170 \n\
00171 # Camera index\n\
00172 uint32 camindex\n\
00173 \n\
00174 # Point index\n\
00175 uint32 pointindex\n\
00176 \n\
00177 # Projection into the image plane\n\
00178 float64 u\n\
00179 float64 v\n\
00180 float64 d\n\
00181 \n\
00182 # Is this a stereo projection? (true if stereo, false if monocular)\n\
00183 bool stereo\n\
00184 \n\
00185 # Use a covariance matrix?\n\
00186 bool usecovariance\n\
00187 \n\
00188 # A 3x3 covariance matrix describing the error\n\
00189 float64[9] covariance\n\
00190 \n\
00191 \n\
00192 "; }
00193 public:
00194 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00195
00196 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00197
00198 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00199 {
00200 ros::serialization::OStream stream(write_ptr, 1000000000);
00201 ros::serialization::serialize(stream, header);
00202 ros::serialization::serialize(stream, nodes);
00203 ros::serialization::serialize(stream, points);
00204 ros::serialization::serialize(stream, projections);
00205 return stream.getData();
00206 }
00207
00208 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00209 {
00210 ros::serialization::IStream stream(read_ptr, 1000000000);
00211 ros::serialization::deserialize(stream, header);
00212 ros::serialization::deserialize(stream, nodes);
00213 ros::serialization::deserialize(stream, points);
00214 ros::serialization::deserialize(stream, projections);
00215 return stream.getData();
00216 }
00217
00218 ROS_DEPRECATED virtual uint32_t serializationLength() const
00219 {
00220 uint32_t size = 0;
00221 size += ros::serialization::serializationLength(header);
00222 size += ros::serialization::serializationLength(nodes);
00223 size += ros::serialization::serializationLength(points);
00224 size += ros::serialization::serializationLength(projections);
00225 return size;
00226 }
00227
00228 typedef boost::shared_ptr< ::sba::Frame_<ContainerAllocator> > Ptr;
00229 typedef boost::shared_ptr< ::sba::Frame_<ContainerAllocator> const> ConstPtr;
00230 };
00231 typedef ::sba::Frame_<std::allocator<void> > Frame;
00232
00233 typedef boost::shared_ptr< ::sba::Frame> FramePtr;
00234 typedef boost::shared_ptr< ::sba::Frame const> FrameConstPtr;
00235
00236
00237 template<typename ContainerAllocator>
00238 std::ostream& operator<<(std::ostream& s, const ::sba::Frame_<ContainerAllocator> & v)
00239 {
00240 ros::message_operations::Printer< ::sba::Frame_<ContainerAllocator> >::stream(s, "", v);
00241 return s;}
00242
00243 }
00244
00245 namespace ros
00246 {
00247 namespace message_traits
00248 {
00249 template<class ContainerAllocator>
00250 struct MD5Sum< ::sba::Frame_<ContainerAllocator> > {
00251 static const char* value()
00252 {
00253 return "418ca143f82258a762de2cff21411737";
00254 }
00255
00256 static const char* value(const ::sba::Frame_<ContainerAllocator> &) { return value(); }
00257 static const uint64_t static_value1 = 0x418ca143f82258a7ULL;
00258 static const uint64_t static_value2 = 0x62de2cff21411737ULL;
00259 };
00260
00261 template<class ContainerAllocator>
00262 struct DataType< ::sba::Frame_<ContainerAllocator> > {
00263 static const char* value()
00264 {
00265 return "sba/Frame";
00266 }
00267
00268 static const char* value(const ::sba::Frame_<ContainerAllocator> &) { return value(); }
00269 };
00270
00271 template<class ContainerAllocator>
00272 struct Definition< ::sba::Frame_<ContainerAllocator> > {
00273 static const char* value()
00274 {
00275 return "# New Frame\n\
00276 Header header\n\
00277 \n\
00278 # New nodes (generally just 1, but want to leave this open)\n\
00279 CameraNode[] nodes\n\
00280 \n\
00281 # New points added from the frame\n\
00282 WorldPoint[] points\n\
00283 \n\
00284 # New projections\n\
00285 Projection[] projections\n\
00286 \n\
00287 ================================================================================\n\
00288 MSG: std_msgs/Header\n\
00289 # Standard metadata for higher-level stamped data types.\n\
00290 # This is generally used to communicate timestamped data \n\
00291 # in a particular coordinate frame.\n\
00292 # \n\
00293 # sequence ID: consecutively increasing ID \n\
00294 uint32 seq\n\
00295 #Two-integer timestamp that is expressed as:\n\
00296 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00297 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00298 # time-handling sugar is provided by the client library\n\
00299 time stamp\n\
00300 #Frame this data is associated with\n\
00301 # 0: no frame\n\
00302 # 1: global frame\n\
00303 string frame_id\n\
00304 \n\
00305 ================================================================================\n\
00306 MSG: sba/CameraNode\n\
00307 # Node Parameters\n\
00308 uint32 index\n\
00309 \n\
00310 # Contains a translation and rotation\n\
00311 geometry_msgs/Transform transform\n\
00312 \n\
00313 # Camera parameters from the K matrix\n\
00314 float64 fx\n\
00315 float64 fy\n\
00316 float64 cx\n\
00317 float64 cy\n\
00318 \n\
00319 # Only relevant for a stereo camera\n\
00320 float64 baseline\n\
00321 \n\
00322 # Whether the camera is fixed in space: i.e., its position is known\n\
00323 bool fixed\n\
00324 \n\
00325 ================================================================================\n\
00326 MSG: geometry_msgs/Transform\n\
00327 # This represents the transform between two coordinate frames in free space.\n\
00328 \n\
00329 Vector3 translation\n\
00330 Quaternion rotation\n\
00331 \n\
00332 ================================================================================\n\
00333 MSG: geometry_msgs/Vector3\n\
00334 # This represents a vector in free space. \n\
00335 \n\
00336 float64 x\n\
00337 float64 y\n\
00338 float64 z\n\
00339 ================================================================================\n\
00340 MSG: geometry_msgs/Quaternion\n\
00341 # This represents an orientation in free space in quaternion form.\n\
00342 \n\
00343 float64 x\n\
00344 float64 y\n\
00345 float64 z\n\
00346 float64 w\n\
00347 \n\
00348 ================================================================================\n\
00349 MSG: sba/WorldPoint\n\
00350 # World Point parameters\n\
00351 \n\
00352 # Point index\n\
00353 uint32 index\n\
00354 \n\
00355 # Coordinates in the world frame\n\
00356 float64 x\n\
00357 float64 y\n\
00358 float64 z\n\
00359 float64 w\n\
00360 \n\
00361 ================================================================================\n\
00362 MSG: sba/Projection\n\
00363 # Projection\n\
00364 \n\
00365 # Camera index\n\
00366 uint32 camindex\n\
00367 \n\
00368 # Point index\n\
00369 uint32 pointindex\n\
00370 \n\
00371 # Projection into the image plane\n\
00372 float64 u\n\
00373 float64 v\n\
00374 float64 d\n\
00375 \n\
00376 # Is this a stereo projection? (true if stereo, false if monocular)\n\
00377 bool stereo\n\
00378 \n\
00379 # Use a covariance matrix?\n\
00380 bool usecovariance\n\
00381 \n\
00382 # A 3x3 covariance matrix describing the error\n\
00383 float64[9] covariance\n\
00384 \n\
00385 \n\
00386 ";
00387 }
00388
00389 static const char* value(const ::sba::Frame_<ContainerAllocator> &) { return value(); }
00390 };
00391
00392 template<class ContainerAllocator> struct HasHeader< ::sba::Frame_<ContainerAllocator> > : public TrueType {};
00393 template<class ContainerAllocator> struct HasHeader< const ::sba::Frame_<ContainerAllocator> > : public TrueType {};
00394 }
00395 }
00396
00397 namespace ros
00398 {
00399 namespace serialization
00400 {
00401
00402 template<class ContainerAllocator> struct Serializer< ::sba::Frame_<ContainerAllocator> >
00403 {
00404 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00405 {
00406 stream.next(m.header);
00407 stream.next(m.nodes);
00408 stream.next(m.points);
00409 stream.next(m.projections);
00410 }
00411
00412 ROS_DECLARE_ALLINONE_SERIALIZER;
00413 };
00414 }
00415 }
00416
00417 namespace ros
00418 {
00419 namespace message_operations
00420 {
00421
00422 template<class ContainerAllocator>
00423 struct Printer< ::sba::Frame_<ContainerAllocator> >
00424 {
00425 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sba::Frame_<ContainerAllocator> & v)
00426 {
00427 s << indent << "header: ";
00428 s << std::endl;
00429 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00430 s << indent << "nodes[]" << std::endl;
00431 for (size_t i = 0; i < v.nodes.size(); ++i)
00432 {
00433 s << indent << " nodes[" << i << "]: ";
00434 s << std::endl;
00435 s << indent;
00436 Printer< ::sba::CameraNode_<ContainerAllocator> >::stream(s, indent + " ", v.nodes[i]);
00437 }
00438 s << indent << "points[]" << std::endl;
00439 for (size_t i = 0; i < v.points.size(); ++i)
00440 {
00441 s << indent << " points[" << i << "]: ";
00442 s << std::endl;
00443 s << indent;
00444 Printer< ::sba::WorldPoint_<ContainerAllocator> >::stream(s, indent + " ", v.points[i]);
00445 }
00446 s << indent << "projections[]" << std::endl;
00447 for (size_t i = 0; i < v.projections.size(); ++i)
00448 {
00449 s << indent << " projections[" << i << "]: ";
00450 s << std::endl;
00451 s << indent;
00452 Printer< ::sba::Projection_<ContainerAllocator> >::stream(s, indent + " ", v.projections[i]);
00453 }
00454 }
00455 };
00456
00457
00458 }
00459 }
00460
00461 #endif // SBA_MESSAGE_FRAME_H
00462