5 #ifndef GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H 6 #define GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H 23 template <
class ContainerAllocator>
43 typedef ::geometry_msgs::Pose_<ContainerAllocator>
_pose_type;
49 typedef std::shared_ptr< ::geometry_msgs::PoseStamped_<ContainerAllocator> >
Ptr;
50 typedef std::shared_ptr< ::geometry_msgs::PoseStamped_<ContainerAllocator>
const>
ConstPtr;
54 typedef ::geometry_msgs::PoseStamped_<std::allocator<void> >
PoseStamped;
63 template<
typename ContainerAllocator>
64 std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PoseStamped_<ContainerAllocator> &
v)
74 namespace message_traits
87 template <
class ContainerAllocator>
92 template <
class ContainerAllocator>
97 template <
class ContainerAllocator>
102 template <
class ContainerAllocator>
107 template <
class ContainerAllocator>
112 template <
class ContainerAllocator>
118 template<
class ContainerAllocator>
123 return "d3812c3cbc69362b77dc0b19b345f8f5";
126 static const char*
value(const ::geometry_msgs::PoseStamped_<ContainerAllocator>&) {
return value(); }
127 static const uint64_t static_value1 = 0xd3812c3cbc69362bULL;
128 static const uint64_t static_value2 = 0x77dc0b19b345f8f5ULL;
131 template<
class ContainerAllocator>
136 return "geometry_msgs/PoseStamped";
139 static const char*
value(const ::geometry_msgs::PoseStamped_<ContainerAllocator>&) {
return value(); }
142 template<
class ContainerAllocator>
147 return "# A Pose with reference coordinate frame and timestamp\n\ 151 ================================================================================\n\ 152 MSG: std_msgs/Header\n\ 153 # Standard metadata for higher-level stamped data types.\n\ 154 # This is generally used to communicate timestamped data \n\ 155 # in a particular coordinate frame.\n\ 157 # sequence ID: consecutively increasing ID \n\ 159 #Two-integer timestamp that is expressed as:\n\ 160 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 161 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 162 # time-handling sugar is provided by the client library\n\ 164 #Frame this data is associated with\n\ 169 ================================================================================\n\ 170 MSG: geometry_msgs/Pose\n\ 171 # A representation of pose in free space, composed of position and orientation. \n\ 173 Quaternion orientation\n\ 175 ================================================================================\n\ 176 MSG: geometry_msgs/Point\n\ 177 # This contains the position of a point in free space\n\ 182 ================================================================================\n\ 183 MSG: geometry_msgs/Quaternion\n\ 184 # This represents an orientation in free space in quaternion form.\n\ 193 static const char*
value(const ::geometry_msgs::PoseStamped_<ContainerAllocator>&) {
return value(); }
201 namespace serialization
208 stream.next(m.header);
220 namespace message_operations
223 template<
class ContainerAllocator>
226 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::geometry_msgs::PoseStamped_<ContainerAllocator>&
v)
228 s << indent <<
"header: ";
231 s << indent <<
"pose: ";
240 #endif // GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H PoseStamped_(const ContainerAllocator &_alloc)
std::shared_ptr< ::geometry_msgs::PoseStamped_< ContainerAllocator > const > ConstPtr
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static const char * value(const ::geometry_msgs::PoseStamped_< ContainerAllocator > &)
static const char * value(const ::geometry_msgs::PoseStamped_< ContainerAllocator > &)
::std_msgs::Header_< ContainerAllocator > _header_type
std::shared_ptr< ::geometry_msgs::PoseStamped const > PoseStampedConstPtr
Specialize to provide the md5sum for a message.
static void stream(Stream &s, const std::string &indent, const ::geometry_msgs::PoseStamped_< ContainerAllocator > &v)
PoseStamped_< ContainerAllocator > Type
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
GLsizei const GLchar *const * string
::geometry_msgs::PoseStamped_< std::allocator< void > > PoseStamped
Specialize to provide the datatype for a message.
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
static void allInOne(Stream &stream, T m)
Stream base-class, provides common functionality for IStream and OStream.
static const char * value()
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
unsigned __int64 uint64_t
static const char * value()
Specialize to provide the definition for a message.
::geometry_msgs::Pose_< ContainerAllocator > _pose_type
static const char * value()
std::shared_ptr< ::geometry_msgs::PoseStamped > PoseStampedPtr
std::shared_ptr< ::geometry_msgs::PoseStamped_< ContainerAllocator > > Ptr
static const char * value(const ::geometry_msgs::PoseStamped_< ContainerAllocator > &)
Templated serialization class. Default implementation provides backwards compatibility with old messa...