$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-srs_public/doc_stacks/2013-03-05_12-22-34.333426/srs_public/srs_msgs/msg/DBGrasp.msg */ 00002 #ifndef SRS_MSGS_MESSAGE_DBGRASP_H 00003 #define SRS_MSGS_MESSAGE_DBGRASP_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 "geometry_msgs/PoseStamped.h" 00018 #include "geometry_msgs/PoseStamped.h" 00019 00020 namespace srs_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct DBGrasp_ { 00024 typedef DBGrasp_<ContainerAllocator> Type; 00025 00026 DBGrasp_() 00027 : object_id(0) 00028 , hand_type() 00029 , sdh_joint_values() 00030 , pre_grasp() 00031 , grasp() 00032 , category() 00033 { 00034 } 00035 00036 DBGrasp_(const ContainerAllocator& _alloc) 00037 : object_id(0) 00038 , hand_type(_alloc) 00039 , sdh_joint_values(_alloc) 00040 , pre_grasp(_alloc) 00041 , grasp(_alloc) 00042 , category(_alloc) 00043 { 00044 } 00045 00046 typedef int32_t _object_id_type; 00047 int32_t object_id; 00048 00049 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _hand_type_type; 00050 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > hand_type; 00051 00052 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _sdh_joint_values_type; 00053 std::vector<double, typename ContainerAllocator::template rebind<double>::other > sdh_joint_values; 00054 00055 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pre_grasp_type; 00056 ::geometry_msgs::PoseStamped_<ContainerAllocator> pre_grasp; 00057 00058 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _grasp_type; 00059 ::geometry_msgs::PoseStamped_<ContainerAllocator> grasp; 00060 00061 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _category_type; 00062 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > category; 00063 00064 00065 ROS_DEPRECATED uint32_t get_sdh_joint_values_size() const { return (uint32_t)sdh_joint_values.size(); } 00066 ROS_DEPRECATED void set_sdh_joint_values_size(uint32_t size) { sdh_joint_values.resize((size_t)size); } 00067 ROS_DEPRECATED void get_sdh_joint_values_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->sdh_joint_values; } 00068 ROS_DEPRECATED void set_sdh_joint_values_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->sdh_joint_values = vec; } 00069 private: 00070 static const char* __s_getDataType_() { return "srs_msgs/DBGrasp"; } 00071 public: 00072 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00073 00074 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00075 00076 private: 00077 static const char* __s_getMD5Sum_() { return "d25a83b2040a10d845751c83e9e78981"; } 00078 public: 00079 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00080 00081 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00082 00083 private: 00084 static const char* __s_getMessageDefinition_() { return "int32 object_id\n\ 00085 string hand_type\n\ 00086 float64[] sdh_joint_values\n\ 00087 geometry_msgs/PoseStamped pre_grasp\n\ 00088 geometry_msgs/PoseStamped grasp\n\ 00089 string category\n\ 00090 \n\ 00091 ================================================================================\n\ 00092 MSG: geometry_msgs/PoseStamped\n\ 00093 # A Pose with reference coordinate frame and timestamp\n\ 00094 Header header\n\ 00095 Pose pose\n\ 00096 \n\ 00097 ================================================================================\n\ 00098 MSG: std_msgs/Header\n\ 00099 # Standard metadata for higher-level stamped data types.\n\ 00100 # This is generally used to communicate timestamped data \n\ 00101 # in a particular coordinate frame.\n\ 00102 # \n\ 00103 # sequence ID: consecutively increasing ID \n\ 00104 uint32 seq\n\ 00105 #Two-integer timestamp that is expressed as:\n\ 00106 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00107 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00108 # time-handling sugar is provided by the client library\n\ 00109 time stamp\n\ 00110 #Frame this data is associated with\n\ 00111 # 0: no frame\n\ 00112 # 1: global frame\n\ 00113 string frame_id\n\ 00114 \n\ 00115 ================================================================================\n\ 00116 MSG: geometry_msgs/Pose\n\ 00117 # A representation of pose in free space, composed of postion and orientation. \n\ 00118 Point position\n\ 00119 Quaternion orientation\n\ 00120 \n\ 00121 ================================================================================\n\ 00122 MSG: geometry_msgs/Point\n\ 00123 # This contains the position of a point in free space\n\ 00124 float64 x\n\ 00125 float64 y\n\ 00126 float64 z\n\ 00127 \n\ 00128 ================================================================================\n\ 00129 MSG: geometry_msgs/Quaternion\n\ 00130 # This represents an orientation in free space in quaternion form.\n\ 00131 \n\ 00132 float64 x\n\ 00133 float64 y\n\ 00134 float64 z\n\ 00135 float64 w\n\ 00136 \n\ 00137 "; } 00138 public: 00139 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00140 00141 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00142 00143 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00144 { 00145 ros::serialization::OStream stream(write_ptr, 1000000000); 00146 ros::serialization::serialize(stream, object_id); 00147 ros::serialization::serialize(stream, hand_type); 00148 ros::serialization::serialize(stream, sdh_joint_values); 00149 ros::serialization::serialize(stream, pre_grasp); 00150 ros::serialization::serialize(stream, grasp); 00151 ros::serialization::serialize(stream, category); 00152 return stream.getData(); 00153 } 00154 00155 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00156 { 00157 ros::serialization::IStream stream(read_ptr, 1000000000); 00158 ros::serialization::deserialize(stream, object_id); 00159 ros::serialization::deserialize(stream, hand_type); 00160 ros::serialization::deserialize(stream, sdh_joint_values); 00161 ros::serialization::deserialize(stream, pre_grasp); 00162 ros::serialization::deserialize(stream, grasp); 00163 ros::serialization::deserialize(stream, category); 00164 return stream.getData(); 00165 } 00166 00167 ROS_DEPRECATED virtual uint32_t serializationLength() const 00168 { 00169 uint32_t size = 0; 00170 size += ros::serialization::serializationLength(object_id); 00171 size += ros::serialization::serializationLength(hand_type); 00172 size += ros::serialization::serializationLength(sdh_joint_values); 00173 size += ros::serialization::serializationLength(pre_grasp); 00174 size += ros::serialization::serializationLength(grasp); 00175 size += ros::serialization::serializationLength(category); 00176 return size; 00177 } 00178 00179 typedef boost::shared_ptr< ::srs_msgs::DBGrasp_<ContainerAllocator> > Ptr; 00180 typedef boost::shared_ptr< ::srs_msgs::DBGrasp_<ContainerAllocator> const> ConstPtr; 00181 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00182 }; // struct DBGrasp 00183 typedef ::srs_msgs::DBGrasp_<std::allocator<void> > DBGrasp; 00184 00185 typedef boost::shared_ptr< ::srs_msgs::DBGrasp> DBGraspPtr; 00186 typedef boost::shared_ptr< ::srs_msgs::DBGrasp const> DBGraspConstPtr; 00187 00188 00189 template<typename ContainerAllocator> 00190 std::ostream& operator<<(std::ostream& s, const ::srs_msgs::DBGrasp_<ContainerAllocator> & v) 00191 { 00192 ros::message_operations::Printer< ::srs_msgs::DBGrasp_<ContainerAllocator> >::stream(s, "", v); 00193 return s;} 00194 00195 } // namespace srs_msgs 00196 00197 namespace ros 00198 { 00199 namespace message_traits 00200 { 00201 template<class ContainerAllocator> struct IsMessage< ::srs_msgs::DBGrasp_<ContainerAllocator> > : public TrueType {}; 00202 template<class ContainerAllocator> struct IsMessage< ::srs_msgs::DBGrasp_<ContainerAllocator> const> : public TrueType {}; 00203 template<class ContainerAllocator> 00204 struct MD5Sum< ::srs_msgs::DBGrasp_<ContainerAllocator> > { 00205 static const char* value() 00206 { 00207 return "d25a83b2040a10d845751c83e9e78981"; 00208 } 00209 00210 static const char* value(const ::srs_msgs::DBGrasp_<ContainerAllocator> &) { return value(); } 00211 static const uint64_t static_value1 = 0xd25a83b2040a10d8ULL; 00212 static const uint64_t static_value2 = 0x45751c83e9e78981ULL; 00213 }; 00214 00215 template<class ContainerAllocator> 00216 struct DataType< ::srs_msgs::DBGrasp_<ContainerAllocator> > { 00217 static const char* value() 00218 { 00219 return "srs_msgs/DBGrasp"; 00220 } 00221 00222 static const char* value(const ::srs_msgs::DBGrasp_<ContainerAllocator> &) { return value(); } 00223 }; 00224 00225 template<class ContainerAllocator> 00226 struct Definition< ::srs_msgs::DBGrasp_<ContainerAllocator> > { 00227 static const char* value() 00228 { 00229 return "int32 object_id\n\ 00230 string hand_type\n\ 00231 float64[] sdh_joint_values\n\ 00232 geometry_msgs/PoseStamped pre_grasp\n\ 00233 geometry_msgs/PoseStamped grasp\n\ 00234 string category\n\ 00235 \n\ 00236 ================================================================================\n\ 00237 MSG: geometry_msgs/PoseStamped\n\ 00238 # A Pose with reference coordinate frame and timestamp\n\ 00239 Header header\n\ 00240 Pose pose\n\ 00241 \n\ 00242 ================================================================================\n\ 00243 MSG: std_msgs/Header\n\ 00244 # Standard metadata for higher-level stamped data types.\n\ 00245 # This is generally used to communicate timestamped data \n\ 00246 # in a particular coordinate frame.\n\ 00247 # \n\ 00248 # sequence ID: consecutively increasing ID \n\ 00249 uint32 seq\n\ 00250 #Two-integer timestamp that is expressed as:\n\ 00251 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00252 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00253 # time-handling sugar is provided by the client library\n\ 00254 time stamp\n\ 00255 #Frame this data is associated with\n\ 00256 # 0: no frame\n\ 00257 # 1: global frame\n\ 00258 string frame_id\n\ 00259 \n\ 00260 ================================================================================\n\ 00261 MSG: geometry_msgs/Pose\n\ 00262 # A representation of pose in free space, composed of postion and orientation. \n\ 00263 Point position\n\ 00264 Quaternion orientation\n\ 00265 \n\ 00266 ================================================================================\n\ 00267 MSG: geometry_msgs/Point\n\ 00268 # This contains the position of a point in free space\n\ 00269 float64 x\n\ 00270 float64 y\n\ 00271 float64 z\n\ 00272 \n\ 00273 ================================================================================\n\ 00274 MSG: geometry_msgs/Quaternion\n\ 00275 # This represents an orientation in free space in quaternion form.\n\ 00276 \n\ 00277 float64 x\n\ 00278 float64 y\n\ 00279 float64 z\n\ 00280 float64 w\n\ 00281 \n\ 00282 "; 00283 } 00284 00285 static const char* value(const ::srs_msgs::DBGrasp_<ContainerAllocator> &) { return value(); } 00286 }; 00287 00288 } // namespace message_traits 00289 } // namespace ros 00290 00291 namespace ros 00292 { 00293 namespace serialization 00294 { 00295 00296 template<class ContainerAllocator> struct Serializer< ::srs_msgs::DBGrasp_<ContainerAllocator> > 00297 { 00298 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00299 { 00300 stream.next(m.object_id); 00301 stream.next(m.hand_type); 00302 stream.next(m.sdh_joint_values); 00303 stream.next(m.pre_grasp); 00304 stream.next(m.grasp); 00305 stream.next(m.category); 00306 } 00307 00308 ROS_DECLARE_ALLINONE_SERIALIZER; 00309 }; // struct DBGrasp_ 00310 } // namespace serialization 00311 } // namespace ros 00312 00313 namespace ros 00314 { 00315 namespace message_operations 00316 { 00317 00318 template<class ContainerAllocator> 00319 struct Printer< ::srs_msgs::DBGrasp_<ContainerAllocator> > 00320 { 00321 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::srs_msgs::DBGrasp_<ContainerAllocator> & v) 00322 { 00323 s << indent << "object_id: "; 00324 Printer<int32_t>::stream(s, indent + " ", v.object_id); 00325 s << indent << "hand_type: "; 00326 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.hand_type); 00327 s << indent << "sdh_joint_values[]" << std::endl; 00328 for (size_t i = 0; i < v.sdh_joint_values.size(); ++i) 00329 { 00330 s << indent << " sdh_joint_values[" << i << "]: "; 00331 Printer<double>::stream(s, indent + " ", v.sdh_joint_values[i]); 00332 } 00333 s << indent << "pre_grasp: "; 00334 s << std::endl; 00335 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.pre_grasp); 00336 s << indent << "grasp: "; 00337 s << std::endl; 00338 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.grasp); 00339 s << indent << "category: "; 00340 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.category); 00341 } 00342 }; 00343 00344 00345 } // namespace message_operations 00346 } // namespace ros 00347 00348 #endif // SRS_MSGS_MESSAGE_DBGRASP_H 00349