// Generated by gencpp from file geometry_msgs/PoseStamped.msg // DO NOT EDIT! #ifndef GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H #define GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H #include #include #include #include #include #include #include #include namespace geometry_msgs { template struct PoseStamped_ { typedef PoseStamped_ Type; PoseStamped_() : header() , pose() { } PoseStamped_(const ContainerAllocator& _alloc) : header(_alloc) , pose(_alloc) { (void)_alloc; } typedef ::std_msgs::Header_ _header_type; _header_type header; typedef ::geometry_msgs::Pose_ _pose_type; _pose_type pose; typedef boost::shared_ptr< ::geometry_msgs::PoseStamped_ > Ptr; typedef boost::shared_ptr< ::geometry_msgs::PoseStamped_ const> ConstPtr; }; // struct PoseStamped_ typedef ::geometry_msgs::PoseStamped_ > PoseStamped; typedef boost::shared_ptr< ::geometry_msgs::PoseStamped > PoseStampedPtr; typedef boost::shared_ptr< ::geometry_msgs::PoseStamped const> PoseStampedConstPtr; // constants requiring out of line definition template std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PoseStamped_ & v) { ros::message_operations::Printer< ::geometry_msgs::PoseStamped_ >::stream(s, "", v); return s; } template bool operator==(const ::geometry_msgs::PoseStamped_ & lhs, const ::geometry_msgs::PoseStamped_ & rhs) { return lhs.header == rhs.header && lhs.pose == rhs.pose; } template bool operator!=(const ::geometry_msgs::PoseStamped_ & lhs, const ::geometry_msgs::PoseStamped_ & rhs) { return !(lhs == rhs); } } // namespace geometry_msgs namespace ros { namespace message_traits { template struct IsMessage< ::geometry_msgs::PoseStamped_ > : TrueType { }; template struct IsMessage< ::geometry_msgs::PoseStamped_ const> : TrueType { }; template struct IsFixedSize< ::geometry_msgs::PoseStamped_ > : FalseType { }; template struct IsFixedSize< ::geometry_msgs::PoseStamped_ const> : FalseType { }; template struct HasHeader< ::geometry_msgs::PoseStamped_ > : TrueType { }; template struct HasHeader< ::geometry_msgs::PoseStamped_ const> : TrueType { }; template struct MD5Sum< ::geometry_msgs::PoseStamped_ > { static const char* value() { return "d3812c3cbc69362b77dc0b19b345f8f5"; } static const char* value(const ::geometry_msgs::PoseStamped_&) { return value(); } static const uint64_t static_value1 = 0xd3812c3cbc69362bULL; static const uint64_t static_value2 = 0x77dc0b19b345f8f5ULL; }; template struct DataType< ::geometry_msgs::PoseStamped_ > { static const char* value() { return "geometry_msgs/PoseStamped"; } static const char* value(const ::geometry_msgs::PoseStamped_&) { return value(); } }; template struct Definition< ::geometry_msgs::PoseStamped_ > { static const char* value() { return "# A Pose with reference coordinate frame and timestamp\n" "Header header\n" "Pose pose\n" "\n" "================================================================================\n" "MSG: std_msgs/Header\n" "# Standard metadata for higher-level stamped data types.\n" "# This is generally used to communicate timestamped data \n" "# in a particular coordinate frame.\n" "# \n" "# sequence ID: consecutively increasing ID \n" "uint32 seq\n" "#Two-integer timestamp that is expressed as:\n" "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n" "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n" "# time-handling sugar is provided by the client library\n" "time stamp\n" "#Frame this data is associated with\n" "string frame_id\n" "\n" "================================================================================\n" "MSG: geometry_msgs/Pose\n" "# A representation of pose in free space, composed of position and orientation. \n" "Point position\n" "Quaternion orientation\n" "\n" "================================================================================\n" "MSG: geometry_msgs/Point\n" "# This contains the position of a point in free space\n" "float64 x\n" "float64 y\n" "float64 z\n" "\n" "================================================================================\n" "MSG: geometry_msgs/Quaternion\n" "# This represents an orientation in free space in quaternion form.\n" "\n" "float64 x\n" "float64 y\n" "float64 z\n" "float64 w\n" ; } static const char* value(const ::geometry_msgs::PoseStamped_&) { return value(); } }; } // namespace message_traits } // namespace ros namespace ros { namespace serialization { template struct Serializer< ::geometry_msgs::PoseStamped_ > { template inline static void allInOne(Stream& stream, T m) { stream.next(m.header); stream.next(m.pose); } ROS_DECLARE_ALLINONE_SERIALIZER }; // struct PoseStamped_ } // namespace serialization } // namespace ros namespace ros { namespace message_operations { template struct Printer< ::geometry_msgs::PoseStamped_ > { template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::PoseStamped_& v) { s << indent << "header: "; s << std::endl; Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); s << indent << "pose: "; s << std::endl; Printer< ::geometry_msgs::Pose_ >::stream(s, indent + " ", v.pose); } }; } // namespace message_operations } // namespace ros #endif // GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H