$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-simulator_gazebo/doc_stacks/2013-03-02_13-33-37.038309/simulator_gazebo/gazebo/msg/ContactState.msg */ 00002 #ifndef GAZEBO_MESSAGE_CONTACTSTATE_H 00003 #define GAZEBO_MESSAGE_CONTACTSTATE_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/Wrench.h" 00018 #include "geometry_msgs/Wrench.h" 00019 #include "geometry_msgs/Vector3.h" 00020 #include "geometry_msgs/Vector3.h" 00021 00022 namespace gazebo 00023 { 00024 template <class ContainerAllocator> 00025 struct ContactState_ { 00026 typedef ContactState_<ContainerAllocator> Type; 00027 00028 ContactState_() 00029 : info() 00030 , geom1_name() 00031 , geom2_name() 00032 , wrenches() 00033 , total_wrench() 00034 , contact_positions() 00035 , contact_normals() 00036 , depths() 00037 { 00038 } 00039 00040 ContactState_(const ContainerAllocator& _alloc) 00041 : info(_alloc) 00042 , geom1_name(_alloc) 00043 , geom2_name(_alloc) 00044 , wrenches(_alloc) 00045 , total_wrench(_alloc) 00046 , contact_positions(_alloc) 00047 , contact_normals(_alloc) 00048 , depths(_alloc) 00049 { 00050 } 00051 00052 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _info_type; 00053 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > info; 00054 00055 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _geom1_name_type; 00056 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > geom1_name; 00057 00058 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _geom2_name_type; 00059 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > geom2_name; 00060 00061 typedef std::vector< ::geometry_msgs::Wrench_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Wrench_<ContainerAllocator> >::other > _wrenches_type; 00062 std::vector< ::geometry_msgs::Wrench_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Wrench_<ContainerAllocator> >::other > wrenches; 00063 00064 typedef ::geometry_msgs::Wrench_<ContainerAllocator> _total_wrench_type; 00065 ::geometry_msgs::Wrench_<ContainerAllocator> total_wrench; 00066 00067 typedef std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > _contact_positions_type; 00068 std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > contact_positions; 00069 00070 typedef std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > _contact_normals_type; 00071 std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > contact_normals; 00072 00073 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _depths_type; 00074 std::vector<double, typename ContainerAllocator::template rebind<double>::other > depths; 00075 00076 00077 ROS_DEPRECATED uint32_t get_wrenches_size() const { return (uint32_t)wrenches.size(); } 00078 ROS_DEPRECATED void set_wrenches_size(uint32_t size) { wrenches.resize((size_t)size); } 00079 ROS_DEPRECATED void get_wrenches_vec(std::vector< ::geometry_msgs::Wrench_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Wrench_<ContainerAllocator> >::other > & vec) const { vec = this->wrenches; } 00080 ROS_DEPRECATED void set_wrenches_vec(const std::vector< ::geometry_msgs::Wrench_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Wrench_<ContainerAllocator> >::other > & vec) { this->wrenches = vec; } 00081 ROS_DEPRECATED uint32_t get_contact_positions_size() const { return (uint32_t)contact_positions.size(); } 00082 ROS_DEPRECATED void set_contact_positions_size(uint32_t size) { contact_positions.resize((size_t)size); } 00083 ROS_DEPRECATED void get_contact_positions_vec(std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > & vec) const { vec = this->contact_positions; } 00084 ROS_DEPRECATED void set_contact_positions_vec(const std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > & vec) { this->contact_positions = vec; } 00085 ROS_DEPRECATED uint32_t get_contact_normals_size() const { return (uint32_t)contact_normals.size(); } 00086 ROS_DEPRECATED void set_contact_normals_size(uint32_t size) { contact_normals.resize((size_t)size); } 00087 ROS_DEPRECATED void get_contact_normals_vec(std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > & vec) const { vec = this->contact_normals; } 00088 ROS_DEPRECATED void set_contact_normals_vec(const std::vector< ::geometry_msgs::Vector3_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Vector3_<ContainerAllocator> >::other > & vec) { this->contact_normals = vec; } 00089 ROS_DEPRECATED uint32_t get_depths_size() const { return (uint32_t)depths.size(); } 00090 ROS_DEPRECATED void set_depths_size(uint32_t size) { depths.resize((size_t)size); } 00091 ROS_DEPRECATED void get_depths_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->depths; } 00092 ROS_DEPRECATED void set_depths_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->depths = vec; } 00093 private: 00094 static const char* __s_getDataType_() { return "gazebo/ContactState"; } 00095 public: 00096 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00097 00098 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00099 00100 private: 00101 static const char* __s_getMD5Sum_() { return "7f688fc24d90d16872fdc9ea8c6e45ab"; } 00102 public: 00103 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00104 00105 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00106 00107 private: 00108 static const char* __s_getMessageDefinition_() { return "#This message is deprecated. Please use the version in gazebo_msgs instead.\n\ 00109 \n\ 00110 string info # text info on this contact\n\ 00111 string geom1_name # name of contact geom1\n\ 00112 string geom2_name # name of contact geom2\n\ 00113 geometry_msgs/Wrench[] wrenches # list of forces/torques\n\ 00114 geometry_msgs/Wrench total_wrench # sum of forces/torques in every DOF\n\ 00115 geometry_msgs/Vector3[] contact_positions # list of contact position\n\ 00116 geometry_msgs/Vector3[] contact_normals # list of contact normals\n\ 00117 float64[] depths # list of penetration depths\n\ 00118 \n\ 00119 ================================================================================\n\ 00120 MSG: geometry_msgs/Wrench\n\ 00121 # This represents force in free space, seperated into \n\ 00122 # it's linear and angular parts. \n\ 00123 Vector3 force\n\ 00124 Vector3 torque\n\ 00125 \n\ 00126 ================================================================================\n\ 00127 MSG: geometry_msgs/Vector3\n\ 00128 # This represents a vector in free space. \n\ 00129 \n\ 00130 float64 x\n\ 00131 float64 y\n\ 00132 float64 z\n\ 00133 "; } 00134 public: 00135 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00136 00137 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00138 00139 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00140 { 00141 ros::serialization::OStream stream(write_ptr, 1000000000); 00142 ros::serialization::serialize(stream, info); 00143 ros::serialization::serialize(stream, geom1_name); 00144 ros::serialization::serialize(stream, geom2_name); 00145 ros::serialization::serialize(stream, wrenches); 00146 ros::serialization::serialize(stream, total_wrench); 00147 ros::serialization::serialize(stream, contact_positions); 00148 ros::serialization::serialize(stream, contact_normals); 00149 ros::serialization::serialize(stream, depths); 00150 return stream.getData(); 00151 } 00152 00153 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00154 { 00155 ros::serialization::IStream stream(read_ptr, 1000000000); 00156 ros::serialization::deserialize(stream, info); 00157 ros::serialization::deserialize(stream, geom1_name); 00158 ros::serialization::deserialize(stream, geom2_name); 00159 ros::serialization::deserialize(stream, wrenches); 00160 ros::serialization::deserialize(stream, total_wrench); 00161 ros::serialization::deserialize(stream, contact_positions); 00162 ros::serialization::deserialize(stream, contact_normals); 00163 ros::serialization::deserialize(stream, depths); 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(info); 00171 size += ros::serialization::serializationLength(geom1_name); 00172 size += ros::serialization::serializationLength(geom2_name); 00173 size += ros::serialization::serializationLength(wrenches); 00174 size += ros::serialization::serializationLength(total_wrench); 00175 size += ros::serialization::serializationLength(contact_positions); 00176 size += ros::serialization::serializationLength(contact_normals); 00177 size += ros::serialization::serializationLength(depths); 00178 return size; 00179 } 00180 00181 typedef boost::shared_ptr< ::gazebo::ContactState_<ContainerAllocator> > Ptr; 00182 typedef boost::shared_ptr< ::gazebo::ContactState_<ContainerAllocator> const> ConstPtr; 00183 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00184 }; // struct ContactState 00185 typedef ::gazebo::ContactState_<std::allocator<void> > ContactState; 00186 00187 typedef boost::shared_ptr< ::gazebo::ContactState> ContactStatePtr; 00188 typedef boost::shared_ptr< ::gazebo::ContactState const> ContactStateConstPtr; 00189 00190 00191 template<typename ContainerAllocator> 00192 std::ostream& operator<<(std::ostream& s, const ::gazebo::ContactState_<ContainerAllocator> & v) 00193 { 00194 ros::message_operations::Printer< ::gazebo::ContactState_<ContainerAllocator> >::stream(s, "", v); 00195 return s;} 00196 00197 } // namespace gazebo 00198 00199 namespace ros 00200 { 00201 namespace message_traits 00202 { 00203 template<class ContainerAllocator> struct IsMessage< ::gazebo::ContactState_<ContainerAllocator> > : public TrueType {}; 00204 template<class ContainerAllocator> struct IsMessage< ::gazebo::ContactState_<ContainerAllocator> const> : public TrueType {}; 00205 template<class ContainerAllocator> 00206 struct MD5Sum< ::gazebo::ContactState_<ContainerAllocator> > { 00207 static const char* value() 00208 { 00209 return "7f688fc24d90d16872fdc9ea8c6e45ab"; 00210 } 00211 00212 static const char* value(const ::gazebo::ContactState_<ContainerAllocator> &) { return value(); } 00213 static const uint64_t static_value1 = 0x7f688fc24d90d168ULL; 00214 static const uint64_t static_value2 = 0x72fdc9ea8c6e45abULL; 00215 }; 00216 00217 template<class ContainerAllocator> 00218 struct DataType< ::gazebo::ContactState_<ContainerAllocator> > { 00219 static const char* value() 00220 { 00221 return "gazebo/ContactState"; 00222 } 00223 00224 static const char* value(const ::gazebo::ContactState_<ContainerAllocator> &) { return value(); } 00225 }; 00226 00227 template<class ContainerAllocator> 00228 struct Definition< ::gazebo::ContactState_<ContainerAllocator> > { 00229 static const char* value() 00230 { 00231 return "#This message is deprecated. Please use the version in gazebo_msgs instead.\n\ 00232 \n\ 00233 string info # text info on this contact\n\ 00234 string geom1_name # name of contact geom1\n\ 00235 string geom2_name # name of contact geom2\n\ 00236 geometry_msgs/Wrench[] wrenches # list of forces/torques\n\ 00237 geometry_msgs/Wrench total_wrench # sum of forces/torques in every DOF\n\ 00238 geometry_msgs/Vector3[] contact_positions # list of contact position\n\ 00239 geometry_msgs/Vector3[] contact_normals # list of contact normals\n\ 00240 float64[] depths # list of penetration depths\n\ 00241 \n\ 00242 ================================================================================\n\ 00243 MSG: geometry_msgs/Wrench\n\ 00244 # This represents force in free space, seperated into \n\ 00245 # it's linear and angular parts. \n\ 00246 Vector3 force\n\ 00247 Vector3 torque\n\ 00248 \n\ 00249 ================================================================================\n\ 00250 MSG: geometry_msgs/Vector3\n\ 00251 # This represents a vector in free space. \n\ 00252 \n\ 00253 float64 x\n\ 00254 float64 y\n\ 00255 float64 z\n\ 00256 "; 00257 } 00258 00259 static const char* value(const ::gazebo::ContactState_<ContainerAllocator> &) { return value(); } 00260 }; 00261 00262 } // namespace message_traits 00263 } // namespace ros 00264 00265 namespace ros 00266 { 00267 namespace serialization 00268 { 00269 00270 template<class ContainerAllocator> struct Serializer< ::gazebo::ContactState_<ContainerAllocator> > 00271 { 00272 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00273 { 00274 stream.next(m.info); 00275 stream.next(m.geom1_name); 00276 stream.next(m.geom2_name); 00277 stream.next(m.wrenches); 00278 stream.next(m.total_wrench); 00279 stream.next(m.contact_positions); 00280 stream.next(m.contact_normals); 00281 stream.next(m.depths); 00282 } 00283 00284 ROS_DECLARE_ALLINONE_SERIALIZER; 00285 }; // struct ContactState_ 00286 } // namespace serialization 00287 } // namespace ros 00288 00289 namespace ros 00290 { 00291 namespace message_operations 00292 { 00293 00294 template<class ContainerAllocator> 00295 struct Printer< ::gazebo::ContactState_<ContainerAllocator> > 00296 { 00297 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::gazebo::ContactState_<ContainerAllocator> & v) 00298 { 00299 s << indent << "info: "; 00300 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.info); 00301 s << indent << "geom1_name: "; 00302 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.geom1_name); 00303 s << indent << "geom2_name: "; 00304 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.geom2_name); 00305 s << indent << "wrenches[]" << std::endl; 00306 for (size_t i = 0; i < v.wrenches.size(); ++i) 00307 { 00308 s << indent << " wrenches[" << i << "]: "; 00309 s << std::endl; 00310 s << indent; 00311 Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + " ", v.wrenches[i]); 00312 } 00313 s << indent << "total_wrench: "; 00314 s << std::endl; 00315 Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + " ", v.total_wrench); 00316 s << indent << "contact_positions[]" << std::endl; 00317 for (size_t i = 0; i < v.contact_positions.size(); ++i) 00318 { 00319 s << indent << " contact_positions[" << i << "]: "; 00320 s << std::endl; 00321 s << indent; 00322 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.contact_positions[i]); 00323 } 00324 s << indent << "contact_normals[]" << std::endl; 00325 for (size_t i = 0; i < v.contact_normals.size(); ++i) 00326 { 00327 s << indent << " contact_normals[" << i << "]: "; 00328 s << std::endl; 00329 s << indent; 00330 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.contact_normals[i]); 00331 } 00332 s << indent << "depths[]" << std::endl; 00333 for (size_t i = 0; i < v.depths.size(); ++i) 00334 { 00335 s << indent << " depths[" << i << "]: "; 00336 Printer<double>::stream(s, indent + " ", v.depths[i]); 00337 } 00338 } 00339 }; 00340 00341 00342 } // namespace message_operations 00343 } // namespace ros 00344 00345 #endif // GAZEBO_MESSAGE_CONTACTSTATE_H 00346