ContactState.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-groovy-simulator_gazebo/doc_stacks/2014-10-06_12-11-14.842894/simulator_gazebo/gazebo_msgs/msg/ContactState.msg */
00002 #ifndef GAZEBO_MSGS_MESSAGE_CONTACTSTATE_H
00003 #define GAZEBO_MSGS_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_msgs
00023 {
00024 template <class ContainerAllocator>
00025 struct ContactState_ {
00026   typedef ContactState_<ContainerAllocator> Type;
00027 
00028   ContactState_()
00029   : info()
00030   , collision1_name()
00031   , collision2_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   , collision1_name(_alloc)
00043   , collision2_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 >  _collision1_name_type;
00056   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  collision1_name;
00057 
00058   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _collision2_name_type;
00059   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  collision2_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   typedef boost::shared_ptr< ::gazebo_msgs::ContactState_<ContainerAllocator> > Ptr;
00078   typedef boost::shared_ptr< ::gazebo_msgs::ContactState_<ContainerAllocator>  const> ConstPtr;
00079   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00080 }; // struct ContactState
00081 typedef  ::gazebo_msgs::ContactState_<std::allocator<void> > ContactState;
00082 
00083 typedef boost::shared_ptr< ::gazebo_msgs::ContactState> ContactStatePtr;
00084 typedef boost::shared_ptr< ::gazebo_msgs::ContactState const> ContactStateConstPtr;
00085 
00086 
00087 template<typename ContainerAllocator>
00088 std::ostream& operator<<(std::ostream& s, const  ::gazebo_msgs::ContactState_<ContainerAllocator> & v)
00089 {
00090   ros::message_operations::Printer< ::gazebo_msgs::ContactState_<ContainerAllocator> >::stream(s, "", v);
00091   return s;}
00092 
00093 } // namespace gazebo_msgs
00094 
00095 namespace ros
00096 {
00097 namespace message_traits
00098 {
00099 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::ContactState_<ContainerAllocator> > : public TrueType {};
00100 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::ContactState_<ContainerAllocator>  const> : public TrueType {};
00101 template<class ContainerAllocator>
00102 struct MD5Sum< ::gazebo_msgs::ContactState_<ContainerAllocator> > {
00103   static const char* value() 
00104   {
00105     return "48c0ffb054b8c444f870cecea1ee50d9";
00106   }
00107 
00108   static const char* value(const  ::gazebo_msgs::ContactState_<ContainerAllocator> &) { return value(); } 
00109   static const uint64_t static_value1 = 0x48c0ffb054b8c444ULL;
00110   static const uint64_t static_value2 = 0xf870cecea1ee50d9ULL;
00111 };
00112 
00113 template<class ContainerAllocator>
00114 struct DataType< ::gazebo_msgs::ContactState_<ContainerAllocator> > {
00115   static const char* value() 
00116   {
00117     return "gazebo_msgs/ContactState";
00118   }
00119 
00120   static const char* value(const  ::gazebo_msgs::ContactState_<ContainerAllocator> &) { return value(); } 
00121 };
00122 
00123 template<class ContainerAllocator>
00124 struct Definition< ::gazebo_msgs::ContactState_<ContainerAllocator> > {
00125   static const char* value() 
00126   {
00127     return "string info                                   # text info on this contact\n\
00128 string collision1_name                        # name of contact collision1\n\
00129 string collision2_name                        # name of contact collision2\n\
00130 geometry_msgs/Wrench[] wrenches               # list of forces/torques\n\
00131 geometry_msgs/Wrench total_wrench             # sum of forces/torques in every DOF\n\
00132 geometry_msgs/Vector3[] contact_positions     # list of contact position\n\
00133 geometry_msgs/Vector3[] contact_normals       # list of contact normals\n\
00134 float64[] depths                              # list of penetration depths\n\
00135 \n\
00136 ================================================================================\n\
00137 MSG: geometry_msgs/Wrench\n\
00138 # This represents force in free space, separated into\n\
00139 # its linear and angular parts.\n\
00140 Vector3  force\n\
00141 Vector3  torque\n\
00142 \n\
00143 ================================================================================\n\
00144 MSG: geometry_msgs/Vector3\n\
00145 # This represents a vector in free space. \n\
00146 \n\
00147 float64 x\n\
00148 float64 y\n\
00149 float64 z\n\
00150 ";
00151   }
00152 
00153   static const char* value(const  ::gazebo_msgs::ContactState_<ContainerAllocator> &) { return value(); } 
00154 };
00155 
00156 } // namespace message_traits
00157 } // namespace ros
00158 
00159 namespace ros
00160 {
00161 namespace serialization
00162 {
00163 
00164 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::ContactState_<ContainerAllocator> >
00165 {
00166   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00167   {
00168     stream.next(m.info);
00169     stream.next(m.collision1_name);
00170     stream.next(m.collision2_name);
00171     stream.next(m.wrenches);
00172     stream.next(m.total_wrench);
00173     stream.next(m.contact_positions);
00174     stream.next(m.contact_normals);
00175     stream.next(m.depths);
00176   }
00177 
00178   ROS_DECLARE_ALLINONE_SERIALIZER;
00179 }; // struct ContactState_
00180 } // namespace serialization
00181 } // namespace ros
00182 
00183 namespace ros
00184 {
00185 namespace message_operations
00186 {
00187 
00188 template<class ContainerAllocator>
00189 struct Printer< ::gazebo_msgs::ContactState_<ContainerAllocator> >
00190 {
00191   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::gazebo_msgs::ContactState_<ContainerAllocator> & v) 
00192   {
00193     s << indent << "info: ";
00194     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.info);
00195     s << indent << "collision1_name: ";
00196     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.collision1_name);
00197     s << indent << "collision2_name: ";
00198     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.collision2_name);
00199     s << indent << "wrenches[]" << std::endl;
00200     for (size_t i = 0; i < v.wrenches.size(); ++i)
00201     {
00202       s << indent << "  wrenches[" << i << "]: ";
00203       s << std::endl;
00204       s << indent;
00205       Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + "    ", v.wrenches[i]);
00206     }
00207     s << indent << "total_wrench: ";
00208 s << std::endl;
00209     Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + "  ", v.total_wrench);
00210     s << indent << "contact_positions[]" << std::endl;
00211     for (size_t i = 0; i < v.contact_positions.size(); ++i)
00212     {
00213       s << indent << "  contact_positions[" << i << "]: ";
00214       s << std::endl;
00215       s << indent;
00216       Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + "    ", v.contact_positions[i]);
00217     }
00218     s << indent << "contact_normals[]" << std::endl;
00219     for (size_t i = 0; i < v.contact_normals.size(); ++i)
00220     {
00221       s << indent << "  contact_normals[" << i << "]: ";
00222       s << std::endl;
00223       s << indent;
00224       Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + "    ", v.contact_normals[i]);
00225     }
00226     s << indent << "depths[]" << std::endl;
00227     for (size_t i = 0; i < v.depths.size(); ++i)
00228     {
00229       s << indent << "  depths[" << i << "]: ";
00230       Printer<double>::stream(s, indent + "  ", v.depths[i]);
00231     }
00232   }
00233 };
00234 
00235 
00236 } // namespace message_operations
00237 } // namespace ros
00238 
00239 #endif // GAZEBO_MSGS_MESSAGE_CONTACTSTATE_H
00240 


gazebo_msgs
Author(s): John Hsu
autogenerated on Mon Oct 6 2014 12:14:33