Go to the documentation of this file.00001
00002 #ifndef GAZEBO_MSGS_MESSAGE_LINKSTATE_H
00003 #define GAZEBO_MSGS_MESSAGE_LINKSTATE_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/Pose.h"
00018 #include "geometry_msgs/Twist.h"
00019
00020 namespace gazebo_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct LinkState_ {
00024 typedef LinkState_<ContainerAllocator> Type;
00025
00026 LinkState_()
00027 : link_name()
00028 , pose()
00029 , twist()
00030 , reference_frame()
00031 {
00032 }
00033
00034 LinkState_(const ContainerAllocator& _alloc)
00035 : link_name(_alloc)
00036 , pose(_alloc)
00037 , twist(_alloc)
00038 , reference_frame(_alloc)
00039 {
00040 }
00041
00042 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _link_name_type;
00043 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > link_name;
00044
00045 typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type;
00046 ::geometry_msgs::Pose_<ContainerAllocator> pose;
00047
00048 typedef ::geometry_msgs::Twist_<ContainerAllocator> _twist_type;
00049 ::geometry_msgs::Twist_<ContainerAllocator> twist;
00050
00051 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _reference_frame_type;
00052 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > reference_frame;
00053
00054
00055 typedef boost::shared_ptr< ::gazebo_msgs::LinkState_<ContainerAllocator> > Ptr;
00056 typedef boost::shared_ptr< ::gazebo_msgs::LinkState_<ContainerAllocator> const> ConstPtr;
00057 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00058 };
00059 typedef ::gazebo_msgs::LinkState_<std::allocator<void> > LinkState;
00060
00061 typedef boost::shared_ptr< ::gazebo_msgs::LinkState> LinkStatePtr;
00062 typedef boost::shared_ptr< ::gazebo_msgs::LinkState const> LinkStateConstPtr;
00063
00064
00065 template<typename ContainerAllocator>
00066 std::ostream& operator<<(std::ostream& s, const ::gazebo_msgs::LinkState_<ContainerAllocator> & v)
00067 {
00068 ros::message_operations::Printer< ::gazebo_msgs::LinkState_<ContainerAllocator> >::stream(s, "", v);
00069 return s;}
00070
00071 }
00072
00073 namespace ros
00074 {
00075 namespace message_traits
00076 {
00077 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::LinkState_<ContainerAllocator> > : public TrueType {};
00078 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::LinkState_<ContainerAllocator> const> : public TrueType {};
00079 template<class ContainerAllocator>
00080 struct MD5Sum< ::gazebo_msgs::LinkState_<ContainerAllocator> > {
00081 static const char* value()
00082 {
00083 return "0818ebbf28ce3a08d48ab1eaa7309ebe";
00084 }
00085
00086 static const char* value(const ::gazebo_msgs::LinkState_<ContainerAllocator> &) { return value(); }
00087 static const uint64_t static_value1 = 0x0818ebbf28ce3a08ULL;
00088 static const uint64_t static_value2 = 0xd48ab1eaa7309ebeULL;
00089 };
00090
00091 template<class ContainerAllocator>
00092 struct DataType< ::gazebo_msgs::LinkState_<ContainerAllocator> > {
00093 static const char* value()
00094 {
00095 return "gazebo_msgs/LinkState";
00096 }
00097
00098 static const char* value(const ::gazebo_msgs::LinkState_<ContainerAllocator> &) { return value(); }
00099 };
00100
00101 template<class ContainerAllocator>
00102 struct Definition< ::gazebo_msgs::LinkState_<ContainerAllocator> > {
00103 static const char* value()
00104 {
00105 return "# @todo: FIXME: sets pose and twist of a link. All children link poses/twists of the URDF tree are not updated accordingly, but should be.\n\
00106 string link_name # link name, link_names are in gazebo scoped name notation, [model_name::body_name]\n\
00107 geometry_msgs/Pose pose # desired pose in reference frame\n\
00108 geometry_msgs/Twist twist # desired twist in reference frame\n\
00109 string reference_frame # set pose/twist relative to the frame of this link/body\n\
00110 # leave empty or \"world\" or \"map\" defaults to world-frame\n\
00111 \n\
00112 ================================================================================\n\
00113 MSG: geometry_msgs/Pose\n\
00114 # A representation of pose in free space, composed of postion and orientation. \n\
00115 Point position\n\
00116 Quaternion orientation\n\
00117 \n\
00118 ================================================================================\n\
00119 MSG: geometry_msgs/Point\n\
00120 # This contains the position of a point in free space\n\
00121 float64 x\n\
00122 float64 y\n\
00123 float64 z\n\
00124 \n\
00125 ================================================================================\n\
00126 MSG: geometry_msgs/Quaternion\n\
00127 # This represents an orientation in free space in quaternion form.\n\
00128 \n\
00129 float64 x\n\
00130 float64 y\n\
00131 float64 z\n\
00132 float64 w\n\
00133 \n\
00134 ================================================================================\n\
00135 MSG: geometry_msgs/Twist\n\
00136 # This expresses velocity in free space broken into its linear and angular parts.\n\
00137 Vector3 linear\n\
00138 Vector3 angular\n\
00139 \n\
00140 ================================================================================\n\
00141 MSG: geometry_msgs/Vector3\n\
00142 # This represents a vector in free space. \n\
00143 \n\
00144 float64 x\n\
00145 float64 y\n\
00146 float64 z\n\
00147 ";
00148 }
00149
00150 static const char* value(const ::gazebo_msgs::LinkState_<ContainerAllocator> &) { return value(); }
00151 };
00152
00153 }
00154 }
00155
00156 namespace ros
00157 {
00158 namespace serialization
00159 {
00160
00161 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::LinkState_<ContainerAllocator> >
00162 {
00163 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00164 {
00165 stream.next(m.link_name);
00166 stream.next(m.pose);
00167 stream.next(m.twist);
00168 stream.next(m.reference_frame);
00169 }
00170
00171 ROS_DECLARE_ALLINONE_SERIALIZER;
00172 };
00173 }
00174 }
00175
00176 namespace ros
00177 {
00178 namespace message_operations
00179 {
00180
00181 template<class ContainerAllocator>
00182 struct Printer< ::gazebo_msgs::LinkState_<ContainerAllocator> >
00183 {
00184 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::gazebo_msgs::LinkState_<ContainerAllocator> & v)
00185 {
00186 s << indent << "link_name: ";
00187 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.link_name);
00188 s << indent << "pose: ";
00189 s << std::endl;
00190 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.pose);
00191 s << indent << "twist: ";
00192 s << std::endl;
00193 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.twist);
00194 s << indent << "reference_frame: ";
00195 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.reference_frame);
00196 }
00197 };
00198
00199
00200 }
00201 }
00202
00203 #endif // GAZEBO_MSGS_MESSAGE_LINKSTATE_H
00204