ForceProcessed.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-gt-ros-pkg/doc_stacks/2013-11-27_11-23-35.692702/hrl/hrl_experiments/hrl_phri_2011/msg/ForceProcessed.msg */
00002 #ifndef HRL_PHRI_2011_MESSAGE_FORCEPROCESSED_H
00003 #define HRL_PHRI_2011_MESSAGE_FORCEPROCESSED_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 "std_msgs/Header.h"
00018 #include "geometry_msgs/TransformStamped.h"
00019 #include "geometry_msgs/Point.h"
00020 #include "geometry_msgs/Vector3.h"
00021 #include "geometry_msgs/Wrench.h"
00022 #include "geometry_msgs/Wrench.h"
00023 #include "geometry_msgs/Point.h"
00024 #include "geometry_msgs/Transform.h"
00025 
00026 namespace hrl_phri_2011
00027 {
00028 template <class ContainerAllocator>
00029 struct ForceProcessed_ {
00030   typedef ForceProcessed_<ContainerAllocator> Type;
00031 
00032   ForceProcessed_()
00033   : header()
00034   , time_offset(0.0)
00035   , tool_frame()
00036   , pc_ind(0)
00037   , pc_pt()
00038   , pc_dist(0.0)
00039   , pc_normal()
00040   , wrench()
00041   , raw_wrench()
00042   , force_magnitude(0.0)
00043   , force_normal(0.0)
00044   , force_tangental(0.0)
00045   , ell_coords()
00046   , tool_ell_frame()
00047   , region()
00048   , user()
00049   , contact_period(0)
00050   , time_from_contact_start(0.0)
00051   {
00052   }
00053 
00054   ForceProcessed_(const ContainerAllocator& _alloc)
00055   : header(_alloc)
00056   , time_offset(0.0)
00057   , tool_frame(_alloc)
00058   , pc_ind(0)
00059   , pc_pt(_alloc)
00060   , pc_dist(0.0)
00061   , pc_normal(_alloc)
00062   , wrench(_alloc)
00063   , raw_wrench(_alloc)
00064   , force_magnitude(0.0)
00065   , force_normal(0.0)
00066   , force_tangental(0.0)
00067   , ell_coords(_alloc)
00068   , tool_ell_frame(_alloc)
00069   , region(_alloc)
00070   , user(_alloc)
00071   , contact_period(0)
00072   , time_from_contact_start(0.0)
00073   {
00074   }
00075 
00076   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
00077    ::std_msgs::Header_<ContainerAllocator>  header;
00078 
00079   typedef float _time_offset_type;
00080   float time_offset;
00081 
00082   typedef  ::geometry_msgs::TransformStamped_<ContainerAllocator>  _tool_frame_type;
00083    ::geometry_msgs::TransformStamped_<ContainerAllocator>  tool_frame;
00084 
00085   typedef int32_t _pc_ind_type;
00086   int32_t pc_ind;
00087 
00088   typedef  ::geometry_msgs::Point_<ContainerAllocator>  _pc_pt_type;
00089    ::geometry_msgs::Point_<ContainerAllocator>  pc_pt;
00090 
00091   typedef float _pc_dist_type;
00092   float pc_dist;
00093 
00094   typedef  ::geometry_msgs::Vector3_<ContainerAllocator>  _pc_normal_type;
00095    ::geometry_msgs::Vector3_<ContainerAllocator>  pc_normal;
00096 
00097   typedef  ::geometry_msgs::Wrench_<ContainerAllocator>  _wrench_type;
00098    ::geometry_msgs::Wrench_<ContainerAllocator>  wrench;
00099 
00100   typedef  ::geometry_msgs::Wrench_<ContainerAllocator>  _raw_wrench_type;
00101    ::geometry_msgs::Wrench_<ContainerAllocator>  raw_wrench;
00102 
00103   typedef float _force_magnitude_type;
00104   float force_magnitude;
00105 
00106   typedef float _force_normal_type;
00107   float force_normal;
00108 
00109   typedef float _force_tangental_type;
00110   float force_tangental;
00111 
00112   typedef  ::geometry_msgs::Point_<ContainerAllocator>  _ell_coords_type;
00113    ::geometry_msgs::Point_<ContainerAllocator>  ell_coords;
00114 
00115   typedef  ::geometry_msgs::Transform_<ContainerAllocator>  _tool_ell_frame_type;
00116    ::geometry_msgs::Transform_<ContainerAllocator>  tool_ell_frame;
00117 
00118   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _region_type;
00119   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  region;
00120 
00121   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _user_type;
00122   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  user;
00123 
00124   typedef int32_t _contact_period_type;
00125   int32_t contact_period;
00126 
00127   typedef float _time_from_contact_start_type;
00128   float time_from_contact_start;
00129 
00130 
00131   typedef boost::shared_ptr< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> > Ptr;
00132   typedef boost::shared_ptr< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator>  const> ConstPtr;
00133   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00134 }; // struct ForceProcessed
00135 typedef  ::hrl_phri_2011::ForceProcessed_<std::allocator<void> > ForceProcessed;
00136 
00137 typedef boost::shared_ptr< ::hrl_phri_2011::ForceProcessed> ForceProcessedPtr;
00138 typedef boost::shared_ptr< ::hrl_phri_2011::ForceProcessed const> ForceProcessedConstPtr;
00139 
00140 
00141 template<typename ContainerAllocator>
00142 std::ostream& operator<<(std::ostream& s, const  ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> & v)
00143 {
00144   ros::message_operations::Printer< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> >::stream(s, "", v);
00145   return s;}
00146 
00147 } // namespace hrl_phri_2011
00148 
00149 namespace ros
00150 {
00151 namespace message_traits
00152 {
00153 template<class ContainerAllocator> struct IsMessage< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> > : public TrueType {};
00154 template<class ContainerAllocator> struct IsMessage< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator>  const> : public TrueType {};
00155 template<class ContainerAllocator>
00156 struct MD5Sum< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> > {
00157   static const char* value() 
00158   {
00159     return "5e1a218134302a1948d1586068f579b8";
00160   }
00161 
00162   static const char* value(const  ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> &) { return value(); } 
00163   static const uint64_t static_value1 = 0x5e1a218134302a19ULL;
00164   static const uint64_t static_value2 = 0x48d1586068f579b8ULL;
00165 };
00166 
00167 template<class ContainerAllocator>
00168 struct DataType< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> > {
00169   static const char* value() 
00170   {
00171     return "hrl_phri_2011/ForceProcessed";
00172   }
00173 
00174   static const char* value(const  ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> &) { return value(); } 
00175 };
00176 
00177 template<class ContainerAllocator>
00178 struct Definition< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> > {
00179   static const char* value() 
00180   {
00181     return "Header header\n\
00182 float32 time_offset\n\
00183 geometry_msgs/TransformStamped tool_frame\n\
00184 \n\
00185 # pointcloud data\n\
00186 int32 pc_ind\n\
00187 geometry_msgs/Point pc_pt\n\
00188 float32 pc_dist\n\
00189 geometry_msgs/Vector3 pc_normal\n\
00190 \n\
00191 # wrench data\n\
00192 geometry_msgs/Wrench wrench\n\
00193 geometry_msgs/Wrench raw_wrench\n\
00194 float32 force_magnitude\n\
00195 float32 force_normal\n\
00196 float32 force_tangental\n\
00197 \n\
00198 # semantic data\n\
00199 geometry_msgs/Point ell_coords\n\
00200 geometry_msgs/Transform tool_ell_frame\n\
00201 string region\n\
00202 string user\n\
00203 int32 contact_period\n\
00204 float32 time_from_contact_start\n\
00205 \n\
00206 ================================================================================\n\
00207 MSG: std_msgs/Header\n\
00208 # Standard metadata for higher-level stamped data types.\n\
00209 # This is generally used to communicate timestamped data \n\
00210 # in a particular coordinate frame.\n\
00211 # \n\
00212 # sequence ID: consecutively increasing ID \n\
00213 uint32 seq\n\
00214 #Two-integer timestamp that is expressed as:\n\
00215 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00216 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00217 # time-handling sugar is provided by the client library\n\
00218 time stamp\n\
00219 #Frame this data is associated with\n\
00220 # 0: no frame\n\
00221 # 1: global frame\n\
00222 string frame_id\n\
00223 \n\
00224 ================================================================================\n\
00225 MSG: geometry_msgs/TransformStamped\n\
00226 # This expresses a transform from coordinate frame header.frame_id\n\
00227 # to the coordinate frame child_frame_id\n\
00228 #\n\
00229 # This message is mostly used by the \n\
00230 # <a href=\"http://www.ros.org/wiki/tf\">tf</a> package. \n\
00231 # See it's documentation for more information.\n\
00232 \n\
00233 Header header\n\
00234 string child_frame_id # the frame id of the child frame\n\
00235 Transform transform\n\
00236 \n\
00237 ================================================================================\n\
00238 MSG: geometry_msgs/Transform\n\
00239 # This represents the transform between two coordinate frames in free space.\n\
00240 \n\
00241 Vector3 translation\n\
00242 Quaternion rotation\n\
00243 \n\
00244 ================================================================================\n\
00245 MSG: geometry_msgs/Vector3\n\
00246 # This represents a vector in free space. \n\
00247 \n\
00248 float64 x\n\
00249 float64 y\n\
00250 float64 z\n\
00251 ================================================================================\n\
00252 MSG: geometry_msgs/Quaternion\n\
00253 # This represents an orientation in free space in quaternion form.\n\
00254 \n\
00255 float64 x\n\
00256 float64 y\n\
00257 float64 z\n\
00258 float64 w\n\
00259 \n\
00260 ================================================================================\n\
00261 MSG: geometry_msgs/Point\n\
00262 # This contains the position of a point in free space\n\
00263 float64 x\n\
00264 float64 y\n\
00265 float64 z\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: geometry_msgs/Wrench\n\
00269 # This represents force in free space, seperated into \n\
00270 # it's linear and angular parts.  \n\
00271 Vector3  force\n\
00272 Vector3  torque\n\
00273 \n\
00274 ";
00275   }
00276 
00277   static const char* value(const  ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> &) { return value(); } 
00278 };
00279 
00280 template<class ContainerAllocator> struct HasHeader< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> > : public TrueType {};
00281 template<class ContainerAllocator> struct HasHeader< const ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> > : public TrueType {};
00282 } // namespace message_traits
00283 } // namespace ros
00284 
00285 namespace ros
00286 {
00287 namespace serialization
00288 {
00289 
00290 template<class ContainerAllocator> struct Serializer< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> >
00291 {
00292   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00293   {
00294     stream.next(m.header);
00295     stream.next(m.time_offset);
00296     stream.next(m.tool_frame);
00297     stream.next(m.pc_ind);
00298     stream.next(m.pc_pt);
00299     stream.next(m.pc_dist);
00300     stream.next(m.pc_normal);
00301     stream.next(m.wrench);
00302     stream.next(m.raw_wrench);
00303     stream.next(m.force_magnitude);
00304     stream.next(m.force_normal);
00305     stream.next(m.force_tangental);
00306     stream.next(m.ell_coords);
00307     stream.next(m.tool_ell_frame);
00308     stream.next(m.region);
00309     stream.next(m.user);
00310     stream.next(m.contact_period);
00311     stream.next(m.time_from_contact_start);
00312   }
00313 
00314   ROS_DECLARE_ALLINONE_SERIALIZER;
00315 }; // struct ForceProcessed_
00316 } // namespace serialization
00317 } // namespace ros
00318 
00319 namespace ros
00320 {
00321 namespace message_operations
00322 {
00323 
00324 template<class ContainerAllocator>
00325 struct Printer< ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> >
00326 {
00327   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::hrl_phri_2011::ForceProcessed_<ContainerAllocator> & v) 
00328   {
00329     s << indent << "header: ";
00330 s << std::endl;
00331     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00332     s << indent << "time_offset: ";
00333     Printer<float>::stream(s, indent + "  ", v.time_offset);
00334     s << indent << "tool_frame: ";
00335 s << std::endl;
00336     Printer< ::geometry_msgs::TransformStamped_<ContainerAllocator> >::stream(s, indent + "  ", v.tool_frame);
00337     s << indent << "pc_ind: ";
00338     Printer<int32_t>::stream(s, indent + "  ", v.pc_ind);
00339     s << indent << "pc_pt: ";
00340 s << std::endl;
00341     Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + "  ", v.pc_pt);
00342     s << indent << "pc_dist: ";
00343     Printer<float>::stream(s, indent + "  ", v.pc_dist);
00344     s << indent << "pc_normal: ";
00345 s << std::endl;
00346     Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + "  ", v.pc_normal);
00347     s << indent << "wrench: ";
00348 s << std::endl;
00349     Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + "  ", v.wrench);
00350     s << indent << "raw_wrench: ";
00351 s << std::endl;
00352     Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + "  ", v.raw_wrench);
00353     s << indent << "force_magnitude: ";
00354     Printer<float>::stream(s, indent + "  ", v.force_magnitude);
00355     s << indent << "force_normal: ";
00356     Printer<float>::stream(s, indent + "  ", v.force_normal);
00357     s << indent << "force_tangental: ";
00358     Printer<float>::stream(s, indent + "  ", v.force_tangental);
00359     s << indent << "ell_coords: ";
00360 s << std::endl;
00361     Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + "  ", v.ell_coords);
00362     s << indent << "tool_ell_frame: ";
00363 s << std::endl;
00364     Printer< ::geometry_msgs::Transform_<ContainerAllocator> >::stream(s, indent + "  ", v.tool_ell_frame);
00365     s << indent << "region: ";
00366     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.region);
00367     s << indent << "user: ";
00368     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.user);
00369     s << indent << "contact_period: ";
00370     Printer<int32_t>::stream(s, indent + "  ", v.contact_period);
00371     s << indent << "time_from_contact_start: ";
00372     Printer<float>::stream(s, indent + "  ", v.time_from_contact_start);
00373   }
00374 };
00375 
00376 
00377 } // namespace message_operations
00378 } // namespace ros
00379 
00380 #endif // HRL_PHRI_2011_MESSAGE_FORCEPROCESSED_H
00381 


hrl_phri_2011
Author(s): Kelsey Hawkins
autogenerated on Wed Nov 27 2013 12:22:40