00001
00002 #ifndef VISP_TRACKER_MESSAGE_MOVINGEDGESITES_H
00003 #define VISP_TRACKER_MESSAGE_MOVINGEDGESITES_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 "visp_tracker/MovingEdgeSite.h"
00015
00016 namespace visp_tracker
00017 {
00018 template <class ContainerAllocator>
00019 struct MovingEdgeSites_ : public ros::Message
00020 {
00021 typedef MovingEdgeSites_<ContainerAllocator> Type;
00022
00023 MovingEdgeSites_()
00024 : header()
00025 , moving_edge_sites()
00026 {
00027 }
00028
00029 MovingEdgeSites_(const ContainerAllocator& _alloc)
00030 : header(_alloc)
00031 , moving_edge_sites(_alloc)
00032 {
00033 }
00034
00035 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00036 ::std_msgs::Header_<ContainerAllocator> header;
00037
00038 typedef std::vector< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> >::other > _moving_edge_sites_type;
00039 std::vector< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> >::other > moving_edge_sites;
00040
00041
00042 ROS_DEPRECATED uint32_t get_moving_edge_sites_size() const { return (uint32_t)moving_edge_sites.size(); }
00043 ROS_DEPRECATED void set_moving_edge_sites_size(uint32_t size) { moving_edge_sites.resize((size_t)size); }
00044 ROS_DEPRECATED void get_moving_edge_sites_vec(std::vector< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> >::other > & vec) const { vec = this->moving_edge_sites; }
00045 ROS_DEPRECATED void set_moving_edge_sites_vec(const std::vector< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> >::other > & vec) { this->moving_edge_sites = vec; }
00046 private:
00047 static const char* __s_getDataType_() { return "visp_tracker/MovingEdgeSites"; }
00048 public:
00049 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00050
00051 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00052
00053 private:
00054 static const char* __s_getMD5Sum_() { return "5293e8601467590a0dabbb34da47310c"; }
00055 public:
00056 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00057
00058 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00059
00060 private:
00061 static const char* __s_getMessageDefinition_() { return "# Stamped list of moving edge positions.\n\
00062 #\n\
00063 # Moving edge positions associated with a particular timestamp.\n\
00064 # Used by the viewer to display moving edge positions and allow\n\
00065 # tracking debug.\n\
00066 \n\
00067 Header header # Header (required for synchronization).\n\
00068 MovingEdgeSite[] moving_edge_sites # List of moving dge sites (i.e. positions).\n\
00069 \n\
00070 ================================================================================\n\
00071 MSG: std_msgs/Header\n\
00072 # Standard metadata for higher-level stamped data types.\n\
00073 # This is generally used to communicate timestamped data \n\
00074 # in a particular coordinate frame.\n\
00075 # \n\
00076 # sequence ID: consecutively increasing ID \n\
00077 uint32 seq\n\
00078 #Two-integer timestamp that is expressed as:\n\
00079 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00080 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00081 # time-handling sugar is provided by the client library\n\
00082 time stamp\n\
00083 #Frame this data is associated with\n\
00084 # 0: no frame\n\
00085 # 1: global frame\n\
00086 string frame_id\n\
00087 \n\
00088 ================================================================================\n\
00089 MSG: visp_tracker/MovingEdgeSite\n\
00090 # Moving edge position.\n\
00091 \n\
00092 float64 x # X position in the image\n\
00093 float64 y # Y position in the image\n\
00094 int32 suppress # Is the moving edge valid?\n\
00095 # - 0: yes\n\
00096 # - 1: no, constrast check has failed.\n\
00097 # - 2: no, threshold check has failed.\n\
00098 # - 3: no, M-estimator check has failed.\n\
00099 # - >=4: no, undocumented reason.\n\
00100 \n\
00101 "; }
00102 public:
00103 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00104
00105 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00106
00107 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00108 {
00109 ros::serialization::OStream stream(write_ptr, 1000000000);
00110 ros::serialization::serialize(stream, header);
00111 ros::serialization::serialize(stream, moving_edge_sites);
00112 return stream.getData();
00113 }
00114
00115 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00116 {
00117 ros::serialization::IStream stream(read_ptr, 1000000000);
00118 ros::serialization::deserialize(stream, header);
00119 ros::serialization::deserialize(stream, moving_edge_sites);
00120 return stream.getData();
00121 }
00122
00123 ROS_DEPRECATED virtual uint32_t serializationLength() const
00124 {
00125 uint32_t size = 0;
00126 size += ros::serialization::serializationLength(header);
00127 size += ros::serialization::serializationLength(moving_edge_sites);
00128 return size;
00129 }
00130
00131 typedef boost::shared_ptr< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> > Ptr;
00132 typedef boost::shared_ptr< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> const> ConstPtr;
00133 };
00134 typedef ::visp_tracker::MovingEdgeSites_<std::allocator<void> > MovingEdgeSites;
00135
00136 typedef boost::shared_ptr< ::visp_tracker::MovingEdgeSites> MovingEdgeSitesPtr;
00137 typedef boost::shared_ptr< ::visp_tracker::MovingEdgeSites const> MovingEdgeSitesConstPtr;
00138
00139
00140 template<typename ContainerAllocator>
00141 std::ostream& operator<<(std::ostream& s, const ::visp_tracker::MovingEdgeSites_<ContainerAllocator> & v)
00142 {
00143 ros::message_operations::Printer< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> >::stream(s, "", v);
00144 return s;}
00145
00146 }
00147
00148 namespace ros
00149 {
00150 namespace message_traits
00151 {
00152 template<class ContainerAllocator>
00153 struct MD5Sum< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> > {
00154 static const char* value()
00155 {
00156 return "5293e8601467590a0dabbb34da47310c";
00157 }
00158
00159 static const char* value(const ::visp_tracker::MovingEdgeSites_<ContainerAllocator> &) { return value(); }
00160 static const uint64_t static_value1 = 0x5293e8601467590aULL;
00161 static const uint64_t static_value2 = 0x0dabbb34da47310cULL;
00162 };
00163
00164 template<class ContainerAllocator>
00165 struct DataType< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> > {
00166 static const char* value()
00167 {
00168 return "visp_tracker/MovingEdgeSites";
00169 }
00170
00171 static const char* value(const ::visp_tracker::MovingEdgeSites_<ContainerAllocator> &) { return value(); }
00172 };
00173
00174 template<class ContainerAllocator>
00175 struct Definition< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> > {
00176 static const char* value()
00177 {
00178 return "# Stamped list of moving edge positions.\n\
00179 #\n\
00180 # Moving edge positions associated with a particular timestamp.\n\
00181 # Used by the viewer to display moving edge positions and allow\n\
00182 # tracking debug.\n\
00183 \n\
00184 Header header # Header (required for synchronization).\n\
00185 MovingEdgeSite[] moving_edge_sites # List of moving dge sites (i.e. positions).\n\
00186 \n\
00187 ================================================================================\n\
00188 MSG: std_msgs/Header\n\
00189 # Standard metadata for higher-level stamped data types.\n\
00190 # This is generally used to communicate timestamped data \n\
00191 # in a particular coordinate frame.\n\
00192 # \n\
00193 # sequence ID: consecutively increasing ID \n\
00194 uint32 seq\n\
00195 #Two-integer timestamp that is expressed as:\n\
00196 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00197 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00198 # time-handling sugar is provided by the client library\n\
00199 time stamp\n\
00200 #Frame this data is associated with\n\
00201 # 0: no frame\n\
00202 # 1: global frame\n\
00203 string frame_id\n\
00204 \n\
00205 ================================================================================\n\
00206 MSG: visp_tracker/MovingEdgeSite\n\
00207 # Moving edge position.\n\
00208 \n\
00209 float64 x # X position in the image\n\
00210 float64 y # Y position in the image\n\
00211 int32 suppress # Is the moving edge valid?\n\
00212 # - 0: yes\n\
00213 # - 1: no, constrast check has failed.\n\
00214 # - 2: no, threshold check has failed.\n\
00215 # - 3: no, M-estimator check has failed.\n\
00216 # - >=4: no, undocumented reason.\n\
00217 \n\
00218 ";
00219 }
00220
00221 static const char* value(const ::visp_tracker::MovingEdgeSites_<ContainerAllocator> &) { return value(); }
00222 };
00223
00224 template<class ContainerAllocator> struct HasHeader< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> > : public TrueType {};
00225 template<class ContainerAllocator> struct HasHeader< const ::visp_tracker::MovingEdgeSites_<ContainerAllocator> > : public TrueType {};
00226 }
00227 }
00228
00229 namespace ros
00230 {
00231 namespace serialization
00232 {
00233
00234 template<class ContainerAllocator> struct Serializer< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> >
00235 {
00236 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00237 {
00238 stream.next(m.header);
00239 stream.next(m.moving_edge_sites);
00240 }
00241
00242 ROS_DECLARE_ALLINONE_SERIALIZER;
00243 };
00244 }
00245 }
00246
00247 namespace ros
00248 {
00249 namespace message_operations
00250 {
00251
00252 template<class ContainerAllocator>
00253 struct Printer< ::visp_tracker::MovingEdgeSites_<ContainerAllocator> >
00254 {
00255 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::visp_tracker::MovingEdgeSites_<ContainerAllocator> & v)
00256 {
00257 s << indent << "header: ";
00258 s << std::endl;
00259 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00260 s << indent << "moving_edge_sites[]" << std::endl;
00261 for (size_t i = 0; i < v.moving_edge_sites.size(); ++i)
00262 {
00263 s << indent << " moving_edge_sites[" << i << "]: ";
00264 s << std::endl;
00265 s << indent;
00266 Printer< ::visp_tracker::MovingEdgeSite_<ContainerAllocator> >::stream(s, indent + " ", v.moving_edge_sites[i]);
00267 }
00268 }
00269 };
00270
00271
00272 }
00273 }
00274
00275 #endif // VISP_TRACKER_MESSAGE_MOVINGEDGESITES_H
00276