00001
00002 #ifndef MOTION_PLANNING_MSGS_MESSAGE_ALLOWEDCONTACTSPECIFICATION_H
00003 #define MOTION_PLANNING_MSGS_MESSAGE_ALLOWEDCONTACTSPECIFICATION_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 "geometric_shapes_msgs/Shape.h"
00014 #include "geometry_msgs/PoseStamped.h"
00015
00016 namespace motion_planning_msgs
00017 {
00018 template <class ContainerAllocator>
00019 struct AllowedContactSpecification_ : public ros::Message
00020 {
00021 typedef AllowedContactSpecification_<ContainerAllocator> Type;
00022
00023 AllowedContactSpecification_()
00024 : name()
00025 , shape()
00026 , pose_stamped()
00027 , link_names()
00028 , penetration_depth(0.0)
00029 {
00030 }
00031
00032 AllowedContactSpecification_(const ContainerAllocator& _alloc)
00033 : name(_alloc)
00034 , shape(_alloc)
00035 , pose_stamped(_alloc)
00036 , link_names(_alloc)
00037 , penetration_depth(0.0)
00038 {
00039 }
00040
00041 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type;
00042 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name;
00043
00044 typedef ::geometric_shapes_msgs::Shape_<ContainerAllocator> _shape_type;
00045 ::geometric_shapes_msgs::Shape_<ContainerAllocator> shape;
00046
00047 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_stamped_type;
00048 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose_stamped;
00049
00050 typedef std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > _link_names_type;
00051 std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > link_names;
00052
00053 typedef double _penetration_depth_type;
00054 double penetration_depth;
00055
00056
00057 ROS_DEPRECATED uint32_t get_link_names_size() const { return (uint32_t)link_names.size(); }
00058 ROS_DEPRECATED void set_link_names_size(uint32_t size) { link_names.resize((size_t)size); }
00059 ROS_DEPRECATED void get_link_names_vec(std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) const { vec = this->link_names; }
00060 ROS_DEPRECATED void set_link_names_vec(const std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) { this->link_names = vec; }
00061 private:
00062 static const char* __s_getDataType_() { return "motion_planning_msgs/AllowedContactSpecification"; }
00063 public:
00064 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00065
00066 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00067
00068 private:
00069 static const char* __s_getMD5Sum_() { return "81f9b47ac49a467ae008d3d9485628a3"; }
00070 public:
00071 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00072
00073 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00074
00075 private:
00076 static const char* __s_getMessageDefinition_() { return "# The names of the regions\n\
00077 string name\n\
00078 \n\
00079 # The shape of the region in the environment\n\
00080 geometric_shapes_msgs/Shape shape\n\
00081 \n\
00082 # The pose of the space defining the region\n\
00083 geometry_msgs/PoseStamped pose_stamped\n\
00084 \n\
00085 # The set of links that will be allowed to have penetration contact within this region\n\
00086 string[] link_names\n\
00087 \n\
00088 # The maximum penetration depth allowed for every link\n\
00089 float64 penetration_depth\n\
00090 ================================================================================\n\
00091 MSG: geometric_shapes_msgs/Shape\n\
00092 byte SPHERE=0\n\
00093 byte BOX=1\n\
00094 byte CYLINDER=2\n\
00095 byte MESH=3\n\
00096 \n\
00097 byte type\n\
00098 \n\
00099 \n\
00100 #### define sphere, box, cylinder ####\n\
00101 # the origin of each shape is considered at the shape's center\n\
00102 \n\
00103 # for sphere\n\
00104 # radius := dimensions[0]\n\
00105 \n\
00106 # for cylinder\n\
00107 # radius := dimensions[0]\n\
00108 # length := dimensions[1]\n\
00109 # the length is along the Z axis\n\
00110 \n\
00111 # for box\n\
00112 # size_x := dimensions[0]\n\
00113 # size_y := dimensions[1]\n\
00114 # size_z := dimensions[2]\n\
00115 float64[] dimensions\n\
00116 \n\
00117 \n\
00118 #### define mesh ####\n\
00119 \n\
00120 # list of triangles; triangle k is defined by tre vertices located\n\
00121 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00122 int32[] triangles\n\
00123 geometry_msgs/Point[] vertices\n\
00124 \n\
00125 ================================================================================\n\
00126 MSG: geometry_msgs/Point\n\
00127 # This contains the position of a point in free space\n\
00128 float64 x\n\
00129 float64 y\n\
00130 float64 z\n\
00131 \n\
00132 ================================================================================\n\
00133 MSG: geometry_msgs/PoseStamped\n\
00134 # A Pose with reference coordinate frame and timestamp\n\
00135 Header header\n\
00136 Pose pose\n\
00137 \n\
00138 ================================================================================\n\
00139 MSG: std_msgs/Header\n\
00140 # Standard metadata for higher-level stamped data types.\n\
00141 # This is generally used to communicate timestamped data \n\
00142 # in a particular coordinate frame.\n\
00143 # \n\
00144 # sequence ID: consecutively increasing ID \n\
00145 uint32 seq\n\
00146 #Two-integer timestamp that is expressed as:\n\
00147 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00148 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00149 # time-handling sugar is provided by the client library\n\
00150 time stamp\n\
00151 #Frame this data is associated with\n\
00152 # 0: no frame\n\
00153 # 1: global frame\n\
00154 string frame_id\n\
00155 \n\
00156 ================================================================================\n\
00157 MSG: geometry_msgs/Pose\n\
00158 # A representation of pose in free space, composed of postion and orientation. \n\
00159 Point position\n\
00160 Quaternion orientation\n\
00161 \n\
00162 ================================================================================\n\
00163 MSG: geometry_msgs/Quaternion\n\
00164 # This represents an orientation in free space in quaternion form.\n\
00165 \n\
00166 float64 x\n\
00167 float64 y\n\
00168 float64 z\n\
00169 float64 w\n\
00170 \n\
00171 "; }
00172 public:
00173 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00174
00175 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00176
00177 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00178 {
00179 ros::serialization::OStream stream(write_ptr, 1000000000);
00180 ros::serialization::serialize(stream, name);
00181 ros::serialization::serialize(stream, shape);
00182 ros::serialization::serialize(stream, pose_stamped);
00183 ros::serialization::serialize(stream, link_names);
00184 ros::serialization::serialize(stream, penetration_depth);
00185 return stream.getData();
00186 }
00187
00188 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00189 {
00190 ros::serialization::IStream stream(read_ptr, 1000000000);
00191 ros::serialization::deserialize(stream, name);
00192 ros::serialization::deserialize(stream, shape);
00193 ros::serialization::deserialize(stream, pose_stamped);
00194 ros::serialization::deserialize(stream, link_names);
00195 ros::serialization::deserialize(stream, penetration_depth);
00196 return stream.getData();
00197 }
00198
00199 ROS_DEPRECATED virtual uint32_t serializationLength() const
00200 {
00201 uint32_t size = 0;
00202 size += ros::serialization::serializationLength(name);
00203 size += ros::serialization::serializationLength(shape);
00204 size += ros::serialization::serializationLength(pose_stamped);
00205 size += ros::serialization::serializationLength(link_names);
00206 size += ros::serialization::serializationLength(penetration_depth);
00207 return size;
00208 }
00209
00210 typedef boost::shared_ptr< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> > Ptr;
00211 typedef boost::shared_ptr< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> const> ConstPtr;
00212 };
00213 typedef ::motion_planning_msgs::AllowedContactSpecification_<std::allocator<void> > AllowedContactSpecification;
00214
00215 typedef boost::shared_ptr< ::motion_planning_msgs::AllowedContactSpecification> AllowedContactSpecificationPtr;
00216 typedef boost::shared_ptr< ::motion_planning_msgs::AllowedContactSpecification const> AllowedContactSpecificationConstPtr;
00217
00218
00219 template<typename ContainerAllocator>
00220 std::ostream& operator<<(std::ostream& s, const ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> & v)
00221 {
00222 ros::message_operations::Printer< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> >::stream(s, "", v);
00223 return s;}
00224
00225 }
00226
00227 namespace ros
00228 {
00229 namespace message_traits
00230 {
00231 template<class ContainerAllocator>
00232 struct MD5Sum< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> > {
00233 static const char* value()
00234 {
00235 return "81f9b47ac49a467ae008d3d9485628a3";
00236 }
00237
00238 static const char* value(const ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> &) { return value(); }
00239 static const uint64_t static_value1 = 0x81f9b47ac49a467aULL;
00240 static const uint64_t static_value2 = 0xe008d3d9485628a3ULL;
00241 };
00242
00243 template<class ContainerAllocator>
00244 struct DataType< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> > {
00245 static const char* value()
00246 {
00247 return "motion_planning_msgs/AllowedContactSpecification";
00248 }
00249
00250 static const char* value(const ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> &) { return value(); }
00251 };
00252
00253 template<class ContainerAllocator>
00254 struct Definition< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> > {
00255 static const char* value()
00256 {
00257 return "# The names of the regions\n\
00258 string name\n\
00259 \n\
00260 # The shape of the region in the environment\n\
00261 geometric_shapes_msgs/Shape shape\n\
00262 \n\
00263 # The pose of the space defining the region\n\
00264 geometry_msgs/PoseStamped pose_stamped\n\
00265 \n\
00266 # The set of links that will be allowed to have penetration contact within this region\n\
00267 string[] link_names\n\
00268 \n\
00269 # The maximum penetration depth allowed for every link\n\
00270 float64 penetration_depth\n\
00271 ================================================================================\n\
00272 MSG: geometric_shapes_msgs/Shape\n\
00273 byte SPHERE=0\n\
00274 byte BOX=1\n\
00275 byte CYLINDER=2\n\
00276 byte MESH=3\n\
00277 \n\
00278 byte type\n\
00279 \n\
00280 \n\
00281 #### define sphere, box, cylinder ####\n\
00282 # the origin of each shape is considered at the shape's center\n\
00283 \n\
00284 # for sphere\n\
00285 # radius := dimensions[0]\n\
00286 \n\
00287 # for cylinder\n\
00288 # radius := dimensions[0]\n\
00289 # length := dimensions[1]\n\
00290 # the length is along the Z axis\n\
00291 \n\
00292 # for box\n\
00293 # size_x := dimensions[0]\n\
00294 # size_y := dimensions[1]\n\
00295 # size_z := dimensions[2]\n\
00296 float64[] dimensions\n\
00297 \n\
00298 \n\
00299 #### define mesh ####\n\
00300 \n\
00301 # list of triangles; triangle k is defined by tre vertices located\n\
00302 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00303 int32[] triangles\n\
00304 geometry_msgs/Point[] vertices\n\
00305 \n\
00306 ================================================================================\n\
00307 MSG: geometry_msgs/Point\n\
00308 # This contains the position of a point in free space\n\
00309 float64 x\n\
00310 float64 y\n\
00311 float64 z\n\
00312 \n\
00313 ================================================================================\n\
00314 MSG: geometry_msgs/PoseStamped\n\
00315 # A Pose with reference coordinate frame and timestamp\n\
00316 Header header\n\
00317 Pose pose\n\
00318 \n\
00319 ================================================================================\n\
00320 MSG: std_msgs/Header\n\
00321 # Standard metadata for higher-level stamped data types.\n\
00322 # This is generally used to communicate timestamped data \n\
00323 # in a particular coordinate frame.\n\
00324 # \n\
00325 # sequence ID: consecutively increasing ID \n\
00326 uint32 seq\n\
00327 #Two-integer timestamp that is expressed as:\n\
00328 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00329 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00330 # time-handling sugar is provided by the client library\n\
00331 time stamp\n\
00332 #Frame this data is associated with\n\
00333 # 0: no frame\n\
00334 # 1: global frame\n\
00335 string frame_id\n\
00336 \n\
00337 ================================================================================\n\
00338 MSG: geometry_msgs/Pose\n\
00339 # A representation of pose in free space, composed of postion and orientation. \n\
00340 Point position\n\
00341 Quaternion orientation\n\
00342 \n\
00343 ================================================================================\n\
00344 MSG: geometry_msgs/Quaternion\n\
00345 # This represents an orientation in free space in quaternion form.\n\
00346 \n\
00347 float64 x\n\
00348 float64 y\n\
00349 float64 z\n\
00350 float64 w\n\
00351 \n\
00352 ";
00353 }
00354
00355 static const char* value(const ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> &) { return value(); }
00356 };
00357
00358 }
00359 }
00360
00361 namespace ros
00362 {
00363 namespace serialization
00364 {
00365
00366 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> >
00367 {
00368 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00369 {
00370 stream.next(m.name);
00371 stream.next(m.shape);
00372 stream.next(m.pose_stamped);
00373 stream.next(m.link_names);
00374 stream.next(m.penetration_depth);
00375 }
00376
00377 ROS_DECLARE_ALLINONE_SERIALIZER;
00378 };
00379 }
00380 }
00381
00382 namespace ros
00383 {
00384 namespace message_operations
00385 {
00386
00387 template<class ContainerAllocator>
00388 struct Printer< ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> >
00389 {
00390 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::motion_planning_msgs::AllowedContactSpecification_<ContainerAllocator> & v)
00391 {
00392 s << indent << "name: ";
00393 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.name);
00394 s << indent << "shape: ";
00395 s << std::endl;
00396 Printer< ::geometric_shapes_msgs::Shape_<ContainerAllocator> >::stream(s, indent + " ", v.shape);
00397 s << indent << "pose_stamped: ";
00398 s << std::endl;
00399 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.pose_stamped);
00400 s << indent << "link_names[]" << std::endl;
00401 for (size_t i = 0; i < v.link_names.size(); ++i)
00402 {
00403 s << indent << " link_names[" << i << "]: ";
00404 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.link_names[i]);
00405 }
00406 s << indent << "penetration_depth: ";
00407 Printer<double>::stream(s, indent + " ", v.penetration_depth);
00408 }
00409 };
00410
00411
00412 }
00413 }
00414
00415 #endif // MOTION_PLANNING_MSGS_MESSAGE_ALLOWEDCONTACTSPECIFICATION_H
00416