00001
00002 #ifndef DYNAMIC_OBS_MSGS_MESSAGE_DYNOBSTRAJECTORY_H
00003 #define DYNAMIC_OBS_MSGS_MESSAGE_DYNOBSTRAJECTORY_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 "geometry_msgs/PoseWithCovarianceStamped.h"
00014
00015 namespace dynamic_obs_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct DynObsTrajectory_ : public ros::Message
00019 {
00020 typedef DynObsTrajectory_<ContainerAllocator> Type;
00021
00022 DynObsTrajectory_()
00023 : probability(0.0)
00024 , exists_after(false)
00025 , points()
00026 {
00027 }
00028
00029 DynObsTrajectory_(const ContainerAllocator& _alloc)
00030 : probability(0.0)
00031 , exists_after(false)
00032 , points(_alloc)
00033 {
00034 }
00035
00036 typedef double _probability_type;
00037 double probability;
00038
00039 typedef uint8_t _exists_after_type;
00040 uint8_t exists_after;
00041
00042 typedef std::vector< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> >::other > _points_type;
00043 std::vector< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> >::other > points;
00044
00045
00046 ROS_DEPRECATED uint32_t get_points_size() const { return (uint32_t)points.size(); }
00047 ROS_DEPRECATED void set_points_size(uint32_t size) { points.resize((size_t)size); }
00048 ROS_DEPRECATED void get_points_vec(std::vector< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> >::other > & vec) const { vec = this->points; }
00049 ROS_DEPRECATED void set_points_vec(const std::vector< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> >::other > & vec) { this->points = vec; }
00050 private:
00051 static const char* __s_getDataType_() { return "dynamic_obs_msgs/DynObsTrajectory"; }
00052 public:
00053 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00054
00055 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00056
00057 private:
00058 static const char* __s_getMD5Sum_() { return "156a490125c0df31fa6557eb672e88ef"; }
00059 public:
00060 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00061
00062 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00063
00064 private:
00065 static const char* __s_getMessageDefinition_() { return "#a dynamic obstacle trajectory\n\
00066 \n\
00067 #the probability of the obstacle following this trajectory\n\
00068 float64 probability\n\
00069 \n\
00070 #whether this obstacle should be treated like a static obstacle at the end of its trajectory (true) \n\
00071 #or the obstacle is ignored after the end of its trajectory (false)\n\
00072 bool exists_after\n\
00073 \n\
00074 #the time parameterized path\n\
00075 geometry_msgs/PoseWithCovarianceStamped[] points\n\
00076 \n\
00077 ================================================================================\n\
00078 MSG: geometry_msgs/PoseWithCovarianceStamped\n\
00079 # This expresses an estimated pose with a reference coordinate frame and timestamp\n\
00080 \n\
00081 Header header\n\
00082 PoseWithCovariance pose\n\
00083 \n\
00084 ================================================================================\n\
00085 MSG: std_msgs/Header\n\
00086 # Standard metadata for higher-level stamped data types.\n\
00087 # This is generally used to communicate timestamped data \n\
00088 # in a particular coordinate frame.\n\
00089 # \n\
00090 # sequence ID: consecutively increasing ID \n\
00091 uint32 seq\n\
00092 #Two-integer timestamp that is expressed as:\n\
00093 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00094 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00095 # time-handling sugar is provided by the client library\n\
00096 time stamp\n\
00097 #Frame this data is associated with\n\
00098 # 0: no frame\n\
00099 # 1: global frame\n\
00100 string frame_id\n\
00101 \n\
00102 ================================================================================\n\
00103 MSG: geometry_msgs/PoseWithCovariance\n\
00104 # This represents a pose in free space with uncertainty.\n\
00105 \n\
00106 Pose pose\n\
00107 \n\
00108 # Row-major representation of the 6x6 covariance matrix\n\
00109 # The orientation parameters use a fixed-axis representation.\n\
00110 # In order, the parameters are:\n\
00111 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
00112 float64[36] covariance\n\
00113 \n\
00114 ================================================================================\n\
00115 MSG: geometry_msgs/Pose\n\
00116 # A representation of pose in free space, composed of postion and orientation. \n\
00117 Point position\n\
00118 Quaternion orientation\n\
00119 \n\
00120 ================================================================================\n\
00121 MSG: geometry_msgs/Point\n\
00122 # This contains the position of a point in free space\n\
00123 float64 x\n\
00124 float64 y\n\
00125 float64 z\n\
00126 \n\
00127 ================================================================================\n\
00128 MSG: geometry_msgs/Quaternion\n\
00129 # This represents an orientation in free space in quaternion form.\n\
00130 \n\
00131 float64 x\n\
00132 float64 y\n\
00133 float64 z\n\
00134 float64 w\n\
00135 \n\
00136 "; }
00137 public:
00138 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00139
00140 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00141
00142 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00143 {
00144 ros::serialization::OStream stream(write_ptr, 1000000000);
00145 ros::serialization::serialize(stream, probability);
00146 ros::serialization::serialize(stream, exists_after);
00147 ros::serialization::serialize(stream, points);
00148 return stream.getData();
00149 }
00150
00151 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00152 {
00153 ros::serialization::IStream stream(read_ptr, 1000000000);
00154 ros::serialization::deserialize(stream, probability);
00155 ros::serialization::deserialize(stream, exists_after);
00156 ros::serialization::deserialize(stream, points);
00157 return stream.getData();
00158 }
00159
00160 ROS_DEPRECATED virtual uint32_t serializationLength() const
00161 {
00162 uint32_t size = 0;
00163 size += ros::serialization::serializationLength(probability);
00164 size += ros::serialization::serializationLength(exists_after);
00165 size += ros::serialization::serializationLength(points);
00166 return size;
00167 }
00168
00169 typedef boost::shared_ptr< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> > Ptr;
00170 typedef boost::shared_ptr< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> const> ConstPtr;
00171 };
00172 typedef ::dynamic_obs_msgs::DynObsTrajectory_<std::allocator<void> > DynObsTrajectory;
00173
00174 typedef boost::shared_ptr< ::dynamic_obs_msgs::DynObsTrajectory> DynObsTrajectoryPtr;
00175 typedef boost::shared_ptr< ::dynamic_obs_msgs::DynObsTrajectory const> DynObsTrajectoryConstPtr;
00176
00177
00178 template<typename ContainerAllocator>
00179 std::ostream& operator<<(std::ostream& s, const ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> & v)
00180 {
00181 ros::message_operations::Printer< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> >::stream(s, "", v);
00182 return s;}
00183
00184 }
00185
00186 namespace ros
00187 {
00188 namespace message_traits
00189 {
00190 template<class ContainerAllocator>
00191 struct MD5Sum< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> > {
00192 static const char* value()
00193 {
00194 return "156a490125c0df31fa6557eb672e88ef";
00195 }
00196
00197 static const char* value(const ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> &) { return value(); }
00198 static const uint64_t static_value1 = 0x156a490125c0df31ULL;
00199 static const uint64_t static_value2 = 0xfa6557eb672e88efULL;
00200 };
00201
00202 template<class ContainerAllocator>
00203 struct DataType< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> > {
00204 static const char* value()
00205 {
00206 return "dynamic_obs_msgs/DynObsTrajectory";
00207 }
00208
00209 static const char* value(const ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> &) { return value(); }
00210 };
00211
00212 template<class ContainerAllocator>
00213 struct Definition< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> > {
00214 static const char* value()
00215 {
00216 return "#a dynamic obstacle trajectory\n\
00217 \n\
00218 #the probability of the obstacle following this trajectory\n\
00219 float64 probability\n\
00220 \n\
00221 #whether this obstacle should be treated like a static obstacle at the end of its trajectory (true) \n\
00222 #or the obstacle is ignored after the end of its trajectory (false)\n\
00223 bool exists_after\n\
00224 \n\
00225 #the time parameterized path\n\
00226 geometry_msgs/PoseWithCovarianceStamped[] points\n\
00227 \n\
00228 ================================================================================\n\
00229 MSG: geometry_msgs/PoseWithCovarianceStamped\n\
00230 # This expresses an estimated pose with a reference coordinate frame and timestamp\n\
00231 \n\
00232 Header header\n\
00233 PoseWithCovariance pose\n\
00234 \n\
00235 ================================================================================\n\
00236 MSG: std_msgs/Header\n\
00237 # Standard metadata for higher-level stamped data types.\n\
00238 # This is generally used to communicate timestamped data \n\
00239 # in a particular coordinate frame.\n\
00240 # \n\
00241 # sequence ID: consecutively increasing ID \n\
00242 uint32 seq\n\
00243 #Two-integer timestamp that is expressed as:\n\
00244 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00245 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00246 # time-handling sugar is provided by the client library\n\
00247 time stamp\n\
00248 #Frame this data is associated with\n\
00249 # 0: no frame\n\
00250 # 1: global frame\n\
00251 string frame_id\n\
00252 \n\
00253 ================================================================================\n\
00254 MSG: geometry_msgs/PoseWithCovariance\n\
00255 # This represents a pose in free space with uncertainty.\n\
00256 \n\
00257 Pose pose\n\
00258 \n\
00259 # Row-major representation of the 6x6 covariance matrix\n\
00260 # The orientation parameters use a fixed-axis representation.\n\
00261 # In order, the parameters are:\n\
00262 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
00263 float64[36] covariance\n\
00264 \n\
00265 ================================================================================\n\
00266 MSG: geometry_msgs/Pose\n\
00267 # A representation of pose in free space, composed of postion and orientation. \n\
00268 Point position\n\
00269 Quaternion orientation\n\
00270 \n\
00271 ================================================================================\n\
00272 MSG: geometry_msgs/Point\n\
00273 # This contains the position of a point in free space\n\
00274 float64 x\n\
00275 float64 y\n\
00276 float64 z\n\
00277 \n\
00278 ================================================================================\n\
00279 MSG: geometry_msgs/Quaternion\n\
00280 # This represents an orientation in free space in quaternion form.\n\
00281 \n\
00282 float64 x\n\
00283 float64 y\n\
00284 float64 z\n\
00285 float64 w\n\
00286 \n\
00287 ";
00288 }
00289
00290 static const char* value(const ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> &) { return value(); }
00291 };
00292
00293 }
00294 }
00295
00296 namespace ros
00297 {
00298 namespace serialization
00299 {
00300
00301 template<class ContainerAllocator> struct Serializer< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> >
00302 {
00303 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00304 {
00305 stream.next(m.probability);
00306 stream.next(m.exists_after);
00307 stream.next(m.points);
00308 }
00309
00310 ROS_DECLARE_ALLINONE_SERIALIZER;
00311 };
00312 }
00313 }
00314
00315 namespace ros
00316 {
00317 namespace message_operations
00318 {
00319
00320 template<class ContainerAllocator>
00321 struct Printer< ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> >
00322 {
00323 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::dynamic_obs_msgs::DynObsTrajectory_<ContainerAllocator> & v)
00324 {
00325 s << indent << "probability: ";
00326 Printer<double>::stream(s, indent + " ", v.probability);
00327 s << indent << "exists_after: ";
00328 Printer<uint8_t>::stream(s, indent + " ", v.exists_after);
00329 s << indent << "points[]" << std::endl;
00330 for (size_t i = 0; i < v.points.size(); ++i)
00331 {
00332 s << indent << " points[" << i << "]: ";
00333 s << std::endl;
00334 s << indent;
00335 Printer< ::geometry_msgs::PoseWithCovarianceStamped_<ContainerAllocator> >::stream(s, indent + " ", v.points[i]);
00336 }
00337 }
00338 };
00339
00340
00341 }
00342 }
00343
00344 #endif // DYNAMIC_OBS_MSGS_MESSAGE_DYNOBSTRAJECTORY_H
00345