$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-arm_navigation/doc_stacks/2013-03-01_14-05-03.553953/arm_navigation/arm_navigation_msgs/msg/CollisionObject.msg */ 00002 #ifndef ARM_NAVIGATION_MSGS_MESSAGE_COLLISIONOBJECT_H 00003 #define ARM_NAVIGATION_MSGS_MESSAGE_COLLISIONOBJECT_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 #include "std_msgs/Header.h" 00018 #include "arm_navigation_msgs/CollisionObjectOperation.h" 00019 #include "arm_navigation_msgs/Shape.h" 00020 #include "geometry_msgs/Pose.h" 00021 00022 namespace arm_navigation_msgs 00023 { 00024 template <class ContainerAllocator> 00025 struct CollisionObject_ { 00026 typedef CollisionObject_<ContainerAllocator> Type; 00027 00028 CollisionObject_() 00029 : header() 00030 , id() 00031 , padding(0.0) 00032 , operation() 00033 , shapes() 00034 , poses() 00035 { 00036 } 00037 00038 CollisionObject_(const ContainerAllocator& _alloc) 00039 : header(_alloc) 00040 , id(_alloc) 00041 , padding(0.0) 00042 , operation(_alloc) 00043 , shapes(_alloc) 00044 , poses(_alloc) 00045 { 00046 } 00047 00048 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00049 ::std_msgs::Header_<ContainerAllocator> header; 00050 00051 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _id_type; 00052 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > id; 00053 00054 typedef float _padding_type; 00055 float padding; 00056 00057 typedef ::arm_navigation_msgs::CollisionObjectOperation_<ContainerAllocator> _operation_type; 00058 ::arm_navigation_msgs::CollisionObjectOperation_<ContainerAllocator> operation; 00059 00060 typedef std::vector< ::arm_navigation_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::Shape_<ContainerAllocator> >::other > _shapes_type; 00061 std::vector< ::arm_navigation_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::Shape_<ContainerAllocator> >::other > shapes; 00062 00063 typedef std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > _poses_type; 00064 std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > poses; 00065 00066 00067 ROS_DEPRECATED uint32_t get_shapes_size() const { return (uint32_t)shapes.size(); } 00068 ROS_DEPRECATED void set_shapes_size(uint32_t size) { shapes.resize((size_t)size); } 00069 ROS_DEPRECATED void get_shapes_vec(std::vector< ::arm_navigation_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::Shape_<ContainerAllocator> >::other > & vec) const { vec = this->shapes; } 00070 ROS_DEPRECATED void set_shapes_vec(const std::vector< ::arm_navigation_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::Shape_<ContainerAllocator> >::other > & vec) { this->shapes = vec; } 00071 ROS_DEPRECATED uint32_t get_poses_size() const { return (uint32_t)poses.size(); } 00072 ROS_DEPRECATED void set_poses_size(uint32_t size) { poses.resize((size_t)size); } 00073 ROS_DEPRECATED void get_poses_vec(std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > & vec) const { vec = this->poses; } 00074 ROS_DEPRECATED void set_poses_vec(const std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > & vec) { this->poses = vec; } 00075 private: 00076 static const char* __s_getDataType_() { return "arm_navigation_msgs/CollisionObject"; } 00077 public: 00078 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00079 00080 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00081 00082 private: 00083 static const char* __s_getMD5Sum_() { return "7b972910c23ece1b873b3de0cf92ba97"; } 00084 public: 00085 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00086 00087 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00088 00089 private: 00090 static const char* __s_getMessageDefinition_() { return "# a header, used for interpreting the poses\n\ 00091 Header header\n\ 00092 \n\ 00093 # the id of the object\n\ 00094 string id\n\ 00095 \n\ 00096 # The padding used for filtering points near the object.\n\ 00097 # This does not affect collision checking for the object. \n\ 00098 # Set to negative to get zero padding.\n\ 00099 float32 padding\n\ 00100 \n\ 00101 #This contains what is to be done with the object\n\ 00102 CollisionObjectOperation operation\n\ 00103 \n\ 00104 #the shapes associated with the object\n\ 00105 arm_navigation_msgs/Shape[] shapes\n\ 00106 \n\ 00107 #the poses associated with the shapes - will be transformed using the header\n\ 00108 geometry_msgs/Pose[] poses\n\ 00109 \n\ 00110 ================================================================================\n\ 00111 MSG: std_msgs/Header\n\ 00112 # Standard metadata for higher-level stamped data types.\n\ 00113 # This is generally used to communicate timestamped data \n\ 00114 # in a particular coordinate frame.\n\ 00115 # \n\ 00116 # sequence ID: consecutively increasing ID \n\ 00117 uint32 seq\n\ 00118 #Two-integer timestamp that is expressed as:\n\ 00119 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00120 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00121 # time-handling sugar is provided by the client library\n\ 00122 time stamp\n\ 00123 #Frame this data is associated with\n\ 00124 # 0: no frame\n\ 00125 # 1: global frame\n\ 00126 string frame_id\n\ 00127 \n\ 00128 ================================================================================\n\ 00129 MSG: arm_navigation_msgs/CollisionObjectOperation\n\ 00130 #Puts the object into the environment\n\ 00131 #or updates the object if already added\n\ 00132 byte ADD=0\n\ 00133 \n\ 00134 #Removes the object from the environment entirely\n\ 00135 byte REMOVE=1\n\ 00136 \n\ 00137 #Only valid within the context of a CollisionAttachedObject message\n\ 00138 #Will be ignored if sent with an CollisionObject message\n\ 00139 #Takes an attached object, detaches from the attached link\n\ 00140 #But adds back in as regular object\n\ 00141 byte DETACH_AND_ADD_AS_OBJECT=2\n\ 00142 \n\ 00143 #Only valid within the context of a CollisionAttachedObject message\n\ 00144 #Will be ignored if sent with an CollisionObject message\n\ 00145 #Takes current object in the environment and removes it as\n\ 00146 #a regular object\n\ 00147 byte ATTACH_AND_REMOVE_AS_OBJECT=3\n\ 00148 \n\ 00149 # Byte code for operation\n\ 00150 byte operation\n\ 00151 \n\ 00152 ================================================================================\n\ 00153 MSG: arm_navigation_msgs/Shape\n\ 00154 byte SPHERE=0\n\ 00155 byte BOX=1\n\ 00156 byte CYLINDER=2\n\ 00157 byte MESH=3\n\ 00158 \n\ 00159 byte type\n\ 00160 \n\ 00161 \n\ 00162 #### define sphere, box, cylinder ####\n\ 00163 # the origin of each shape is considered at the shape's center\n\ 00164 \n\ 00165 # for sphere\n\ 00166 # radius := dimensions[0]\n\ 00167 \n\ 00168 # for cylinder\n\ 00169 # radius := dimensions[0]\n\ 00170 # length := dimensions[1]\n\ 00171 # the length is along the Z axis\n\ 00172 \n\ 00173 # for box\n\ 00174 # size_x := dimensions[0]\n\ 00175 # size_y := dimensions[1]\n\ 00176 # size_z := dimensions[2]\n\ 00177 float64[] dimensions\n\ 00178 \n\ 00179 \n\ 00180 #### define mesh ####\n\ 00181 \n\ 00182 # list of triangles; triangle k is defined by tre vertices located\n\ 00183 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\ 00184 int32[] triangles\n\ 00185 geometry_msgs/Point[] vertices\n\ 00186 \n\ 00187 ================================================================================\n\ 00188 MSG: geometry_msgs/Point\n\ 00189 # This contains the position of a point in free space\n\ 00190 float64 x\n\ 00191 float64 y\n\ 00192 float64 z\n\ 00193 \n\ 00194 ================================================================================\n\ 00195 MSG: geometry_msgs/Pose\n\ 00196 # A representation of pose in free space, composed of postion and orientation. \n\ 00197 Point position\n\ 00198 Quaternion orientation\n\ 00199 \n\ 00200 ================================================================================\n\ 00201 MSG: geometry_msgs/Quaternion\n\ 00202 # This represents an orientation in free space in quaternion form.\n\ 00203 \n\ 00204 float64 x\n\ 00205 float64 y\n\ 00206 float64 z\n\ 00207 float64 w\n\ 00208 \n\ 00209 "; } 00210 public: 00211 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00212 00213 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00214 00215 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00216 { 00217 ros::serialization::OStream stream(write_ptr, 1000000000); 00218 ros::serialization::serialize(stream, header); 00219 ros::serialization::serialize(stream, id); 00220 ros::serialization::serialize(stream, padding); 00221 ros::serialization::serialize(stream, operation); 00222 ros::serialization::serialize(stream, shapes); 00223 ros::serialization::serialize(stream, poses); 00224 return stream.getData(); 00225 } 00226 00227 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00228 { 00229 ros::serialization::IStream stream(read_ptr, 1000000000); 00230 ros::serialization::deserialize(stream, header); 00231 ros::serialization::deserialize(stream, id); 00232 ros::serialization::deserialize(stream, padding); 00233 ros::serialization::deserialize(stream, operation); 00234 ros::serialization::deserialize(stream, shapes); 00235 ros::serialization::deserialize(stream, poses); 00236 return stream.getData(); 00237 } 00238 00239 ROS_DEPRECATED virtual uint32_t serializationLength() const 00240 { 00241 uint32_t size = 0; 00242 size += ros::serialization::serializationLength(header); 00243 size += ros::serialization::serializationLength(id); 00244 size += ros::serialization::serializationLength(padding); 00245 size += ros::serialization::serializationLength(operation); 00246 size += ros::serialization::serializationLength(shapes); 00247 size += ros::serialization::serializationLength(poses); 00248 return size; 00249 } 00250 00251 typedef boost::shared_ptr< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > Ptr; 00252 typedef boost::shared_ptr< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> const> ConstPtr; 00253 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00254 }; // struct CollisionObject 00255 typedef ::arm_navigation_msgs::CollisionObject_<std::allocator<void> > CollisionObject; 00256 00257 typedef boost::shared_ptr< ::arm_navigation_msgs::CollisionObject> CollisionObjectPtr; 00258 typedef boost::shared_ptr< ::arm_navigation_msgs::CollisionObject const> CollisionObjectConstPtr; 00259 00260 00261 template<typename ContainerAllocator> 00262 std::ostream& operator<<(std::ostream& s, const ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> & v) 00263 { 00264 ros::message_operations::Printer< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> >::stream(s, "", v); 00265 return s;} 00266 00267 } // namespace arm_navigation_msgs 00268 00269 namespace ros 00270 { 00271 namespace message_traits 00272 { 00273 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > : public TrueType {}; 00274 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> const> : public TrueType {}; 00275 template<class ContainerAllocator> 00276 struct MD5Sum< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > { 00277 static const char* value() 00278 { 00279 return "7b972910c23ece1b873b3de0cf92ba97"; 00280 } 00281 00282 static const char* value(const ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> &) { return value(); } 00283 static const uint64_t static_value1 = 0x7b972910c23ece1bULL; 00284 static const uint64_t static_value2 = 0x873b3de0cf92ba97ULL; 00285 }; 00286 00287 template<class ContainerAllocator> 00288 struct DataType< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > { 00289 static const char* value() 00290 { 00291 return "arm_navigation_msgs/CollisionObject"; 00292 } 00293 00294 static const char* value(const ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> &) { return value(); } 00295 }; 00296 00297 template<class ContainerAllocator> 00298 struct Definition< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > { 00299 static const char* value() 00300 { 00301 return "# a header, used for interpreting the poses\n\ 00302 Header header\n\ 00303 \n\ 00304 # the id of the object\n\ 00305 string id\n\ 00306 \n\ 00307 # The padding used for filtering points near the object.\n\ 00308 # This does not affect collision checking for the object. \n\ 00309 # Set to negative to get zero padding.\n\ 00310 float32 padding\n\ 00311 \n\ 00312 #This contains what is to be done with the object\n\ 00313 CollisionObjectOperation operation\n\ 00314 \n\ 00315 #the shapes associated with the object\n\ 00316 arm_navigation_msgs/Shape[] shapes\n\ 00317 \n\ 00318 #the poses associated with the shapes - will be transformed using the header\n\ 00319 geometry_msgs/Pose[] poses\n\ 00320 \n\ 00321 ================================================================================\n\ 00322 MSG: std_msgs/Header\n\ 00323 # Standard metadata for higher-level stamped data types.\n\ 00324 # This is generally used to communicate timestamped data \n\ 00325 # in a particular coordinate frame.\n\ 00326 # \n\ 00327 # sequence ID: consecutively increasing ID \n\ 00328 uint32 seq\n\ 00329 #Two-integer timestamp that is expressed as:\n\ 00330 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00331 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00332 # time-handling sugar is provided by the client library\n\ 00333 time stamp\n\ 00334 #Frame this data is associated with\n\ 00335 # 0: no frame\n\ 00336 # 1: global frame\n\ 00337 string frame_id\n\ 00338 \n\ 00339 ================================================================================\n\ 00340 MSG: arm_navigation_msgs/CollisionObjectOperation\n\ 00341 #Puts the object into the environment\n\ 00342 #or updates the object if already added\n\ 00343 byte ADD=0\n\ 00344 \n\ 00345 #Removes the object from the environment entirely\n\ 00346 byte REMOVE=1\n\ 00347 \n\ 00348 #Only valid within the context of a CollisionAttachedObject message\n\ 00349 #Will be ignored if sent with an CollisionObject message\n\ 00350 #Takes an attached object, detaches from the attached link\n\ 00351 #But adds back in as regular object\n\ 00352 byte DETACH_AND_ADD_AS_OBJECT=2\n\ 00353 \n\ 00354 #Only valid within the context of a CollisionAttachedObject message\n\ 00355 #Will be ignored if sent with an CollisionObject message\n\ 00356 #Takes current object in the environment and removes it as\n\ 00357 #a regular object\n\ 00358 byte ATTACH_AND_REMOVE_AS_OBJECT=3\n\ 00359 \n\ 00360 # Byte code for operation\n\ 00361 byte operation\n\ 00362 \n\ 00363 ================================================================================\n\ 00364 MSG: arm_navigation_msgs/Shape\n\ 00365 byte SPHERE=0\n\ 00366 byte BOX=1\n\ 00367 byte CYLINDER=2\n\ 00368 byte MESH=3\n\ 00369 \n\ 00370 byte type\n\ 00371 \n\ 00372 \n\ 00373 #### define sphere, box, cylinder ####\n\ 00374 # the origin of each shape is considered at the shape's center\n\ 00375 \n\ 00376 # for sphere\n\ 00377 # radius := dimensions[0]\n\ 00378 \n\ 00379 # for cylinder\n\ 00380 # radius := dimensions[0]\n\ 00381 # length := dimensions[1]\n\ 00382 # the length is along the Z axis\n\ 00383 \n\ 00384 # for box\n\ 00385 # size_x := dimensions[0]\n\ 00386 # size_y := dimensions[1]\n\ 00387 # size_z := dimensions[2]\n\ 00388 float64[] dimensions\n\ 00389 \n\ 00390 \n\ 00391 #### define mesh ####\n\ 00392 \n\ 00393 # list of triangles; triangle k is defined by tre vertices located\n\ 00394 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\ 00395 int32[] triangles\n\ 00396 geometry_msgs/Point[] vertices\n\ 00397 \n\ 00398 ================================================================================\n\ 00399 MSG: geometry_msgs/Point\n\ 00400 # This contains the position of a point in free space\n\ 00401 float64 x\n\ 00402 float64 y\n\ 00403 float64 z\n\ 00404 \n\ 00405 ================================================================================\n\ 00406 MSG: geometry_msgs/Pose\n\ 00407 # A representation of pose in free space, composed of postion and orientation. \n\ 00408 Point position\n\ 00409 Quaternion orientation\n\ 00410 \n\ 00411 ================================================================================\n\ 00412 MSG: geometry_msgs/Quaternion\n\ 00413 # This represents an orientation in free space in quaternion form.\n\ 00414 \n\ 00415 float64 x\n\ 00416 float64 y\n\ 00417 float64 z\n\ 00418 float64 w\n\ 00419 \n\ 00420 "; 00421 } 00422 00423 static const char* value(const ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> &) { return value(); } 00424 }; 00425 00426 template<class ContainerAllocator> struct HasHeader< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > : public TrueType {}; 00427 template<class ContainerAllocator> struct HasHeader< const ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > : public TrueType {}; 00428 } // namespace message_traits 00429 } // namespace ros 00430 00431 namespace ros 00432 { 00433 namespace serialization 00434 { 00435 00436 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > 00437 { 00438 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00439 { 00440 stream.next(m.header); 00441 stream.next(m.id); 00442 stream.next(m.padding); 00443 stream.next(m.operation); 00444 stream.next(m.shapes); 00445 stream.next(m.poses); 00446 } 00447 00448 ROS_DECLARE_ALLINONE_SERIALIZER; 00449 }; // struct CollisionObject_ 00450 } // namespace serialization 00451 } // namespace ros 00452 00453 namespace ros 00454 { 00455 namespace message_operations 00456 { 00457 00458 template<class ContainerAllocator> 00459 struct Printer< ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> > 00460 { 00461 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::arm_navigation_msgs::CollisionObject_<ContainerAllocator> & v) 00462 { 00463 s << indent << "header: "; 00464 s << std::endl; 00465 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00466 s << indent << "id: "; 00467 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.id); 00468 s << indent << "padding: "; 00469 Printer<float>::stream(s, indent + " ", v.padding); 00470 s << indent << "operation: "; 00471 s << std::endl; 00472 Printer< ::arm_navigation_msgs::CollisionObjectOperation_<ContainerAllocator> >::stream(s, indent + " ", v.operation); 00473 s << indent << "shapes[]" << std::endl; 00474 for (size_t i = 0; i < v.shapes.size(); ++i) 00475 { 00476 s << indent << " shapes[" << i << "]: "; 00477 s << std::endl; 00478 s << indent; 00479 Printer< ::arm_navigation_msgs::Shape_<ContainerAllocator> >::stream(s, indent + " ", v.shapes[i]); 00480 } 00481 s << indent << "poses[]" << std::endl; 00482 for (size_t i = 0; i < v.poses.size(); ++i) 00483 { 00484 s << indent << " poses[" << i << "]: "; 00485 s << std::endl; 00486 s << indent; 00487 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.poses[i]); 00488 } 00489 } 00490 }; 00491 00492 00493 } // namespace message_operations 00494 } // namespace ros 00495 00496 #endif // ARM_NAVIGATION_MSGS_MESSAGE_COLLISIONOBJECT_H 00497