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