├── msg ├── Empty.msg ├── Bool.msg ├── Char.msg ├── Int32.msg ├── Int64.msg ├── Byte.msg ├── Float32.msg ├── Float64.msg ├── Int16.msg ├── Int8.msg ├── Time.msg ├── UInt32.msg ├── UInt64.msg ├── UInt8.msg ├── String.msg ├── UInt16.msg ├── Duration.msg ├── ColorRGBA.msg ├── MultiArrayDimension.msg ├── ByteMultiArray.msg ├── Int16MultiArray.msg ├── Int32MultiArray.msg ├── Int64MultiArray.msg ├── Int8MultiArray.msg ├── UInt16MultiArray.msg ├── UInt32MultiArray.msg ├── UInt64MultiArray.msg ├── UInt8MultiArray.msg ├── Float32MultiArray.msg ├── Float64MultiArray.msg ├── Header.msg └── MultiArrayLayout.msg ├── .gitignore ├── README.md ├── CHANGELOG.rst ├── CMakeLists.txt ├── package.xml └── include └── std_msgs ├── builtin_bool.h ├── builtin_int8.h ├── builtin_int16.h ├── builtin_int32.h ├── builtin_int64.h ├── builtin_uint8.h ├── builtin_double.h ├── builtin_float.h ├── builtin_uint16.h ├── builtin_uint32.h ├── builtin_uint64.h ├── trait_macros.h ├── builtin_string.h └── header_deprecated_def.h /msg/Empty.msg: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | -------------------------------------------------------------------------------- /msg/Bool.msg: -------------------------------------------------------------------------------- 1 | bool data -------------------------------------------------------------------------------- /msg/Char.msg: -------------------------------------------------------------------------------- 1 | char data -------------------------------------------------------------------------------- /msg/Int32.msg: -------------------------------------------------------------------------------- 1 | int32 data -------------------------------------------------------------------------------- /msg/Int64.msg: -------------------------------------------------------------------------------- 1 | int64 data -------------------------------------------------------------------------------- /msg/Byte.msg: -------------------------------------------------------------------------------- 1 | byte data 2 | -------------------------------------------------------------------------------- /msg/Float32.msg: -------------------------------------------------------------------------------- 1 | float32 data -------------------------------------------------------------------------------- /msg/Float64.msg: -------------------------------------------------------------------------------- 1 | float64 data -------------------------------------------------------------------------------- /msg/Int16.msg: -------------------------------------------------------------------------------- 1 | int16 data 2 | -------------------------------------------------------------------------------- /msg/Int8.msg: -------------------------------------------------------------------------------- 1 | int8 data 2 | -------------------------------------------------------------------------------- /msg/Time.msg: -------------------------------------------------------------------------------- 1 | time data 2 | -------------------------------------------------------------------------------- /msg/UInt32.msg: -------------------------------------------------------------------------------- 1 | uint32 data -------------------------------------------------------------------------------- /msg/UInt64.msg: -------------------------------------------------------------------------------- 1 | uint64 data -------------------------------------------------------------------------------- /msg/UInt8.msg: -------------------------------------------------------------------------------- 1 | uint8 data 2 | -------------------------------------------------------------------------------- /msg/String.msg: -------------------------------------------------------------------------------- 1 | string data 2 | -------------------------------------------------------------------------------- /msg/UInt16.msg: -------------------------------------------------------------------------------- 1 | uint16 data 2 | -------------------------------------------------------------------------------- /msg/Duration.msg: -------------------------------------------------------------------------------- 1 | duration data 2 | -------------------------------------------------------------------------------- /msg/ColorRGBA.msg: -------------------------------------------------------------------------------- 1 | float32 r 2 | float32 g 3 | float32 b 4 | float32 a 5 | -------------------------------------------------------------------------------- /msg/MultiArrayDimension.msg: -------------------------------------------------------------------------------- 1 | string label # label of given dimension 2 | uint32 size # size of given dimension (in type units) 3 | uint32 stride # stride of given dimension -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Archived - ROS 1 End-of-life 2 | 3 | This repository contains ROS 1 packages. 4 | The last supported ROS 1 release, ROS Noetic, [officially reached end of life on May 31st, 2025](https://bit.ly/NoeticEOL). 5 | 6 | -------------------------------------------------------------------------------- /msg/ByteMultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | byte[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/Int16MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | int16[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/Int32MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | int32[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/Int64MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | int64[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/Int8MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | int8[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/UInt16MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | uint16[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/UInt32MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | uint32[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/UInt64MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | uint64[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/UInt8MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | uint8[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/Float32MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | float32[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /msg/Float64MultiArray.msg: -------------------------------------------------------------------------------- 1 | # Please look at the MultiArrayLayout message definition for 2 | # documentation on all multiarrays. 3 | 4 | MultiArrayLayout layout # specification of data layout 5 | float64[] data # array of data 6 | 7 | -------------------------------------------------------------------------------- /CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package std_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.5.14 (2025-04-10) 6 | ------------------- 7 | * Update package maintainers. (`#16 `_) 8 | * Contributors: Michel Hidalgo 9 | -------------------------------------------------------------------------------- /msg/Header.msg: -------------------------------------------------------------------------------- 1 | # Standard metadata for higher-level stamped data types. 2 | # This is generally used to communicate timestamped data 3 | # in a particular coordinate frame. 4 | # 5 | # sequence ID: consecutively increasing ID 6 | uint32 seq 7 | #Two-integer timestamp that is expressed as: 8 | # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') 9 | # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') 10 | # time-handling sugar is provided by the client library 11 | time stamp 12 | #Frame this data is associated with 13 | string frame_id 14 | -------------------------------------------------------------------------------- /msg/MultiArrayLayout.msg: -------------------------------------------------------------------------------- 1 | # The multiarray declares a generic multi-dimensional array of a 2 | # particular data type. Dimensions are ordered from outer most 3 | # to inner most. 4 | 5 | MultiArrayDimension[] dim # Array of dimension properties 6 | uint32 data_offset # padding elements at front of data 7 | 8 | # Accessors should ALWAYS be written in terms of dimension stride 9 | # and specified outer-most dimension first. 10 | # 11 | # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] 12 | # 13 | # A standard, 3-channel 640x480 image with interleaved color channels 14 | # would be specified as: 15 | # 16 | # dim[0].label = "height" 17 | # dim[0].size = 480 18 | # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) 19 | # dim[1].label = "width" 20 | # dim[1].size = 640 21 | # dim[1].stride = 3*640 = 1920 22 | # dim[2].label = "channel" 23 | # dim[2].size = 3 24 | # dim[2].stride = 3 25 | # 26 | # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. 27 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(std_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | Bool.msg 10 | Byte.msg 11 | ByteMultiArray.msg 12 | Char.msg 13 | ColorRGBA.msg 14 | Duration.msg 15 | Empty.msg 16 | Float32.msg 17 | Float32MultiArray.msg 18 | Float64.msg 19 | Float64MultiArray.msg 20 | Header.msg 21 | Int16.msg 22 | Int16MultiArray.msg 23 | Int32.msg 24 | Int32MultiArray.msg 25 | Int64.msg 26 | Int64MultiArray.msg 27 | Int8.msg 28 | Int8MultiArray.msg 29 | MultiArrayDimension.msg 30 | MultiArrayLayout.msg 31 | String.msg 32 | Time.msg 33 | UInt16.msg 34 | UInt16MultiArray.msg 35 | UInt32.msg 36 | UInt32MultiArray.msg 37 | UInt64.msg 38 | UInt64MultiArray.msg 39 | UInt8.msg 40 | UInt8MultiArray.msg 41 | ) 42 | 43 | generate_messages() 44 | 45 | catkin_package( 46 | INCLUDE_DIRS include 47 | CATKIN_DEPENDS message_runtime) 48 | 49 | install(DIRECTORY include/std_msgs/ 50 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 51 | PATTERN "*.h") 52 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | std_msgs 3 | 0.5.14 4 | 5 | Standard ROS Messages including common message types representing primitive data types and other basic message constructs, such as multiarrays. 6 | For common, generic robot-specific message types, please see common_msgs. 7 | 8 | Michel Hidalgo 9 | BSD 10 | 11 | http://www.ros.org/wiki/std_msgs 12 | https://github.com/ros/std_msgs 13 | https://github.com/ros/std_msgs/issues 14 | Morgan Quigley 15 | Ken Conley 16 | Jeremy Leibs 17 | Tully Foote 18 | 19 | catkin 20 | 21 | message_generation 22 | 23 | message_runtime 24 | 25 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_bool.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_BOOL_H 29 | #define STD_MSGS_BUILTIN_BOOL_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(bool, Bool, 0x8b94c1b53db61fb6ULL, 0xaed406028ad6332aULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_int8.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT8_H 29 | #define STD_MSGS_BUILTIN_INT8_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int8_t, Int8, 0x27ffa0c9c4b8fb84ULL, 0x92252bcad9e5c57bULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_int16.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT16_H 29 | #define STD_MSGS_BUILTIN_INT16_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int16_t, Int16, 0x8524586e34fbd7cbULL, 0x1c08c5f5f1ca0e57ULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_int32.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT32_H 29 | #define STD_MSGS_BUILTIN_INT32_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int32_t, Int32, 0xda5909fbe378aeafULL, 0x85e547e830cc1bb7ULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_int64.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT64_H 29 | #define STD_MSGS_BUILTIN_INT64_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int64_t, Int64, 0x34add168574510e6ULL, 0xe17f5d23ecc077efULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_uint8.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT8_H 29 | #define STD_MSGS_BUILTIN_UINT8_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint8_t, UInt8, 0x7c8164229e7d2c17ULL, 0xeb95e9231617fdeeULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_double.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_DOUBLE_H 29 | #define STD_MSGS_BUILTIN_DOUBLE_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(double, Float64, 0xfdb28210bfa9d7c9ULL, 0x1146260178d9a584ULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_float.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_FLOAT_H 29 | #define STD_MSGS_BUILTIN_FLOAT_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(float, Float32, 0x73fcbf46b49191e6ULL, 0x72908e50842a83d4ULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_uint16.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT16_H 29 | #define STD_MSGS_BUILTIN_UINT16_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint16_t, UInt16, 0x1df79edf208b629fULL, 0xe6b81923a544552dULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_uint32.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT32_H 29 | #define STD_MSGS_BUILTIN_UINT32_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint32_t, UInt32, 0x304a39449588c7f8ULL, 0xce2df6e8001c5fceULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_uint64.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT64_H 29 | #define STD_MSGS_BUILTIN_UINT64_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint64_t, UInt64, 0x1b2a79973e8bf53dULL, 0x7b53acb71299cb57ULL) 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /include/std_msgs/trait_macros.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Copyright (C) 2009, Willow Garage, Inc. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * * Redistributions of source code must retain the above copyright notice, 8 | * this list of conditions and the following disclaimer. 9 | * * Redistributions in binary form must reproduce the above copyright 10 | * notice, this list of conditions and the following disclaimer in the 11 | * documentation and/or other materials provided with the distribution. 12 | * * Neither the names of Willow Garage, Inc. nor the names of its 13 | * contributors may be used to endorse or promote products derived from 14 | * this software without specific prior written permission. 15 | * 16 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 17 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 18 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 19 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 20 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 21 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 22 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 23 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 24 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 25 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 26 | * POSSIBILITY OF SUCH DAMAGE. 27 | */ 28 | 29 | #ifndef STD_MSGS_TRAIT_MACROS_H 30 | #define STD_MSGS_TRAIT_MACROS_H 31 | 32 | #define STD_MSGS_DEFINE_BUILTIN_TRAITS(builtin, msg, static_md5sum1, static_md5sum2) \ 33 | namespace ros \ 34 | { \ 35 | namespace message_traits \ 36 | { \ 37 | \ 38 | template<> struct MD5Sum \ 39 | { \ 40 | static const char* value() \ 41 | { \ 42 | return MD5Sum::value(); \ 43 | } \ 44 | \ 45 | static const char* value(const builtin&) \ 46 | { \ 47 | return value(); \ 48 | } \ 49 | }; \ 50 | \ 51 | template<> struct DataType \ 52 | { \ 53 | static const char* value() \ 54 | { \ 55 | return DataType::value(); \ 56 | } \ 57 | \ 58 | static const char* value(const builtin&) \ 59 | { \ 60 | return value(); \ 61 | } \ 62 | }; \ 63 | \ 64 | template<> struct Definition \ 65 | { \ 66 | static const char* value() \ 67 | { \ 68 | return Definition::value(); \ 69 | } \ 70 | \ 71 | static const char* value(const builtin&) \ 72 | { \ 73 | return value(); \ 74 | } \ 75 | }; \ 76 | \ 77 | } \ 78 | } 79 | 80 | #endif // STD_MSGS_TRAIT_MACROS_H 81 | -------------------------------------------------------------------------------- /include/std_msgs/builtin_string.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_STRING_H 29 | #define STD_MSGS_BUILTIN_STRING_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | namespace ros 35 | { 36 | namespace message_traits 37 | { 38 | 39 | template 40 | struct MD5Sum, ContainerAllocator> > 41 | { 42 | static const char* value() 43 | { 44 | ROS_STATIC_ASSERT(MD5Sum::static_value1 == 0x992ce8a1687cec8cULL); 45 | ROS_STATIC_ASSERT(MD5Sum::static_value2 == 0x8bd883ec73ca41d1ULL); 46 | return MD5Sum >::value(); 47 | } 48 | 49 | static const char* value(const std::basic_string, ContainerAllocator>&) 50 | { 51 | return value(); 52 | } 53 | }; 54 | 55 | template 56 | struct DataType, ContainerAllocator > > 57 | { 58 | static const char* value() 59 | { 60 | return DataType >::value(); 61 | } 62 | 63 | static const char* value(const std::basic_string, ContainerAllocator >&) 64 | { 65 | return value(); 66 | } 67 | }; 68 | 69 | template 70 | struct Definition, ContainerAllocator > > 71 | { 72 | static const char* value() 73 | { 74 | return Definition >::value(); 75 | } 76 | 77 | static const char* value(const std::basic_string, ContainerAllocator >&) 78 | { 79 | return value(); 80 | } 81 | }; 82 | 83 | } 84 | } 85 | 86 | #endif 87 | -------------------------------------------------------------------------------- /include/std_msgs/header_deprecated_def.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_INCLUDING_HEADER_DEPRECATED_DEF 29 | #error("Do not include this file directly. Instead, include std_msgs/Header.h") 30 | #endif 31 | 32 | namespace roslib 33 | { 34 | template 35 | struct Header_ : public std_msgs::Header_ 36 | { 37 | typedef Header_ Type; 38 | 39 | ROS_DEPRECATED Header_() 40 | { 41 | } 42 | 43 | ROS_DEPRECATED Header_(const ContainerAllocator& _alloc) 44 | : std_msgs::Header_(_alloc) 45 | { 46 | } 47 | 48 | ROS_DEPRECATED Header_(const std_msgs::Header_& rhs) 49 | { 50 | *this = rhs; 51 | } 52 | 53 | ROS_DEPRECATED Type& operator=(const std_msgs::Header_& rhs) 54 | { 55 | if (this == &rhs) 56 | return *this; 57 | this->seq = rhs.seq; 58 | this->stamp = rhs.stamp; 59 | this->frame_id = rhs.frame_id; 60 | return *this; 61 | } 62 | 63 | ROS_DEPRECATED operator std_msgs::Header_() 64 | { 65 | std_msgs::Header_ h; 66 | h.seq = this->seq; 67 | h.stamp = this->stamp; 68 | h.frame_id = this->frame_id; 69 | return h; 70 | } 71 | 72 | private: 73 | static const char* __s_getDataType_() { return "roslib/Header"; } 74 | public: 75 | static const std::string __s_getDataType() { return __s_getDataType_(); } 76 | 77 | const std::string __getDataType() const { return __s_getDataType_(); } 78 | 79 | private: 80 | static const char* __s_getMD5Sum_() { return "2176decaecbce78abc3b96ef049fabed"; } 81 | public: 82 | static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 83 | 84 | const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 85 | 86 | private: 87 | static const char* __s_getMessageDefinition_() { return "# Standard metadata for higher-level stamped data types.\n\ 88 | # This is generally used to communicate timestamped data \n\ 89 | # in a particular coordinate frame.\n\ 90 | # \n\ 91 | # sequence ID: consecutively increasing ID \n\ 92 | uint32 seq\n\ 93 | #Two-integer timestamp that is expressed as:\n\ 94 | # * stamp.secs: seconds (stamp_secs) since epoch\n\ 95 | # * stamp.nsecs: nanoseconds since stamp_secs\n\ 96 | # time-handling sugar is provided by the client library\n\ 97 | time stamp\n\ 98 | #Frame this data is associated with\n\ 99 | # 0: no frame\n\ 100 | # 1: global frame\n\ 101 | string frame_id\n\ 102 | \n\ 103 | "; } 104 | public: 105 | static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 106 | 107 | const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 108 | 109 | virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 110 | { 111 | ros::serialization::OStream stream(write_ptr, 1000000000); 112 | ros::serialization::serialize(stream, this->seq); 113 | ros::serialization::serialize(stream, this->stamp); 114 | ros::serialization::serialize(stream, this->frame_id); 115 | return stream.getData(); 116 | } 117 | 118 | virtual uint8_t *deserialize(uint8_t *read_ptr) 119 | { 120 | ros::serialization::IStream stream(read_ptr, 1000000000); 121 | ros::serialization::deserialize(stream, this->seq); 122 | ros::serialization::deserialize(stream, this->stamp); 123 | ros::serialization::deserialize(stream, this->frame_id); 124 | return stream.getData(); 125 | } 126 | 127 | virtual uint32_t serializationLength() const 128 | { 129 | uint32_t size = 0; 130 | size += ros::serialization::serializationLength(this->seq); 131 | size += ros::serialization::serializationLength(this->stamp); 132 | size += ros::serialization::serializationLength(this->frame_id); 133 | return size; 134 | } 135 | 136 | typedef boost::shared_ptr< ::roslib::Header_ > Ptr; 137 | typedef boost::shared_ptr< ::roslib::Header_ const> ConstPtr; 138 | }; // struct Header 139 | typedef ::roslib::Header_ > Header; 140 | 141 | typedef boost::shared_ptr< ::roslib::Header> HeaderPtr; 142 | typedef boost::shared_ptr< ::roslib::Header const> HeaderConstPtr; 143 | 144 | 145 | template 146 | std::ostream& operator<<(std::ostream& s, const ::roslib::Header_ & v) 147 | { 148 | ros::message_operations::Printer< ::roslib::Header_ >::stream(s, "", v); 149 | return s;} 150 | 151 | } // namespace roslib 152 | 153 | namespace ros 154 | { 155 | namespace message_traits 156 | { 157 | template 158 | struct MD5Sum< ::roslib::Header_ > { 159 | static const char* value() 160 | { 161 | return "2176decaecbce78abc3b96ef049fabed"; 162 | } 163 | 164 | static const char* value(const ::roslib::Header_ &) { return value(); } 165 | static const uint64_t static_value1 = 0x2176decaecbce78aULL; 166 | static const uint64_t static_value2 = 0xbc3b96ef049fabedULL; 167 | }; 168 | 169 | template 170 | struct DataType< ::roslib::Header_ > { 171 | static const char* value() 172 | { 173 | return "roslib/Header"; 174 | } 175 | 176 | static const char* value(const ::roslib::Header_ &) { return value(); } 177 | }; 178 | 179 | template 180 | struct Definition< ::roslib::Header_ > { 181 | static const char* value() 182 | { 183 | return "# Standard metadata for higher-level stamped data types.\n\ 184 | # This is generally used to communicate timestamped data \n\ 185 | # in a particular coordinate frame.\n\ 186 | # \n\ 187 | # sequence ID: consecutively increasing ID \n\ 188 | uint32 seq\n\ 189 | #Two-integer timestamp that is expressed as:\n\ 190 | # * stamp.secs: seconds (stamp_secs) since epoch\n\ 191 | # * stamp.nsecs: nanoseconds since stamp_secs\n\ 192 | # time-handling sugar is provided by the client library\n\ 193 | time stamp\n\ 194 | #Frame this data is associated with\n\ 195 | # 0: no frame\n\ 196 | # 1: global frame\n\ 197 | string frame_id\n\ 198 | \n\ 199 | "; 200 | } 201 | 202 | static const char* value(const ::roslib::Header_ &) { return value(); } 203 | }; 204 | 205 | } // namespace message_traits 206 | } // namespace ros 207 | 208 | namespace ros 209 | { 210 | namespace serialization 211 | { 212 | 213 | template struct Serializer< ::roslib::Header_ > 214 | { 215 | template inline static void allInOne(Stream& stream, T m) 216 | { 217 | stream.next(m.seq); 218 | stream.next(m.stamp); 219 | stream.next(m.frame_id); 220 | } 221 | 222 | ROS_DECLARE_ALLINONE_SERIALIZER; 223 | }; // struct Header_ 224 | } // namespace serialization 225 | } // namespace ros 226 | 227 | namespace ros 228 | { 229 | namespace message_operations 230 | { 231 | 232 | template 233 | struct Printer< ::roslib::Header_ > 234 | { 235 | template static void stream(Stream& s, const std::string& indent, const ::roslib::Header_ & v) 236 | { 237 | s << indent << "seq: "; 238 | Printer::stream(s, indent + " ", v.seq); 239 | s << indent << "stamp: "; 240 | Printer::stream(s, indent + " ", v.stamp); 241 | s << indent << "frame_id: "; 242 | Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.frame_id); 243 | } 244 | }; 245 | 246 | 247 | } // namespace message_operations 248 | } // namespace ros 249 | 250 | --------------------------------------------------------------------------------