
capstone_finish
Dependencies: BufferedSerial motor_sn7544
Revision 3:2a3664dc6634, committed 2019-08-13
- Comitter:
- Jeonghoon
- Date:
- Tue Aug 13 05:53:22 2019 +0000
- Parent:
- 2:e98408458d2b
- Child:
- 4:7b63cf3d205f
- Commit message:
- with ROS;
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/BufferedSerial.lib Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/sam_grove/code/BufferedSerial/#7e5e866edd3d
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MbedHardware.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,60 @@ +/* + * MbedHardware + * + * Created on: Aug 17, 2011 + * Author: nucho + */ + +#ifndef ROS_MBED_HARDWARE_H_ +#define ROS_MBED_HARDWARE_H_ + +#include "mbed.h" + +#include "BufferedSerial.h" + +class MbedHardware { + public: + MbedHardware(PinName tx, PinName rx, long baud = 57600) + :iostream(tx, rx){ + baud_ = baud; + t.start(); + } + + MbedHardware() + :iostream(USBTX, USBRX) { + baud_ = 57600; + t.start(); + } + + void setBaud(long baud){ + this->baud_= baud; + } + + int getBaud(){return baud_;} + + void init(){ + iostream.baud(baud_); + } + + int read(){ + if (iostream.readable()) { + return iostream.getc(); + } else { + return -1; + } + }; + void write(uint8_t* data, int length) { + for (int i=0; i<length; i++) + iostream.putc(data[i]); + } + + unsigned long time(){return t.read_ms();} + +protected: + BufferedSerial iostream; + long baud_; + Timer t; +}; + + +#endif /* ROS_MBED_HARDWARE_H_ */
--- a/main.cpp Mon Aug 12 07:12:38 2019 +0000 +++ b/main.cpp Tue Aug 13 05:53:22 2019 +0000 @@ -3,7 +3,13 @@ // #include "mbed.h" #include "ov7670.h" +#include <ros.h> +#include <ros/time.h> +#include <std_msgs/UInt8MultiArray.h> +std_msgs::UInt8MultiArray img; +ros::NodeHandle nh; +ros::Publisher img_pub("image_data", &img); OV7670 camera( @@ -13,65 +19,72 @@ PortB,0xFF, D13,D12,D6) ; // RRST,OE,RCLK -Serial pc(USBTX,USBRX,115200) ; +//Serial pc(USBTX,USBRX,115200) ; Timer t; //#undef QQVGA #define QQVGA #ifdef QQVGA -# define SIZEX (160) -# define SIZEY (120) +# define SIZEX (12) +# define SIZEY (8) #else # define SIZEX (320) # define SIZEY (240) #endif -uint16_t fdata[SIZEX*SIZEY]; + +uint8_t fdata[SIZEX*SIZEY]; + +size_t size = SIZEX*SIZEY; int main() { int last ; - pc.baud(115200) ; +// pc.baud(115200) ; camera.Reset() ; + nh.advertise(img_pub); #ifdef QQVGA // camera.InitQQVGA565(true,false) ; - camera.InitQVGAYUV(true,false); + camera.InitQVGAYUV(false,false); #else //camera.InitQVGA565(true,false) ; #endif - + + // CAPTURE and SEND LOOP t.start(); last = t.read_ms() ; -// while(1) -// { + + + while(1) + { + + img.data_length = size; + camera.CaptureNext() ; while(camera.CaptureDone() == false) ; - printf("Caputure %d(ms)\r\n", t.read_ms() - last) ; + last = t.read_ms() ; camera.ReadStart() ; -// lcd.Lcd_SetCursor(0,0); -// lcd.Lcd_WR_Start(); -// lcd.rsout(1) ; - for (int y = 0; y < SIZEY*SIZEX;y++) { -// pc.printf("\r\n"); - // lcd.Lcd_SetCursor(y,0); - -// lcd.Lcd_WR_Start(); - for (int x = 0;x < SIZEX;x++) { -// pc.printf("%x ",camera.ReadOneWord()); - // lcd.csout(0) ; -// lcd.DataToWrite(camera.ReadOneWord()); -// lcd.csout(1) ; - fdata[SIZEX*SIZEY]=camera.ReadOneWord(); - } + + + for (int y = 0; y < SIZEX*SIZEY ; y++) { + + camera.ReadOneByte(); + fdata[y]=camera.ReadOneByte(); + } - + camera.ReadStop() ; - printf("%d\n", sizeof(fdata)); - printf("FIFO Read & Lcd Out %d(ms)\r\n", t.read_ms() - last) ; last = t.read_ms() ; - // } + + img.data = &fdata[0]; + img_pub.publish(&img); + + + nh.spinOnce(); + wait_ms(1); //max... + } }
--- a/ov7670.h Mon Aug 12 07:12:38 2019 +0000 +++ b/ov7670.h Tue Aug 13 05:53:22 2019 +0000 @@ -433,7 +433,7 @@ } // Data Read (PortIn) - int ReadOneWord(void) + int ReadOneWord(void) //2byte { // int r,r1,r2,r3,r4 ; // rclk = 1 ;
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,46 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_H_ +#define _ROS_H_ + +#include "ros/node_handle.h" +#include "MbedHardware.h" + +namespace ros +{ + typedef NodeHandle_<MbedHardware> NodeHandle; +} + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/builtin_message_traits.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,62 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSLIB_BUILTIN_MESSAGE_TRAITS_H +#define ROSLIB_BUILTIN_MESSAGE_TRAITS_H + +#include "message_traits.h" +#include "ros/time.h" + +namespace ros +{ +namespace message_traits +{ + +#define ROSLIB_CREATE_SIMPLE_TRAITS(Type) \ + template<> struct IsSimple<Type> : public TrueType {}; \ + template<> struct IsFixedSize<Type> : public TrueType {}; + +ROSLIB_CREATE_SIMPLE_TRAITS(uint8_t) +ROSLIB_CREATE_SIMPLE_TRAITS(int8_t) +ROSLIB_CREATE_SIMPLE_TRAITS(uint16_t) +ROSLIB_CREATE_SIMPLE_TRAITS(int16_t) +ROSLIB_CREATE_SIMPLE_TRAITS(uint32_t) +ROSLIB_CREATE_SIMPLE_TRAITS(int32_t) +ROSLIB_CREATE_SIMPLE_TRAITS(uint64_t) +ROSLIB_CREATE_SIMPLE_TRAITS(int64_t) +ROSLIB_CREATE_SIMPLE_TRAITS(float) +ROSLIB_CREATE_SIMPLE_TRAITS(double) +ROSLIB_CREATE_SIMPLE_TRAITS(Time) +ROSLIB_CREATE_SIMPLE_TRAITS(Duration) + +// because std::vector<bool> is not a true vector, bool is not a simple type +template<> struct IsFixedSize<bool> : public TrueType {}; + +} // namespace message_traits +} // namespace ros + +#endif // ROSLIB_BUILTIN_MESSAGE_TRAITS_H
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/datatypes.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,52 @@ +/* + * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef CPP_CORE_TYPES_H +#define CPP_CORE_TYPES_H + +#include <string> +#include <vector> +#include <map> +#include <set> +#include <list> + +#include <boost/shared_ptr.hpp> + + +namespace ros { + +typedef std::vector<std::pair<std::string, std::string> > VP_string; +typedef std::vector<std::string> V_string; +typedef std::set<std::string> S_string; +typedef std::map<std::string, std::string> M_string; +typedef std::pair<std::string, std::string> StringPair; + +typedef boost::shared_ptr<M_string> M_stringPtr; + +} + +#endif // CPP_CORE_TYPES_H \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/duration.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,68 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_DURATION_H_ +#define _ROS_DURATION_H_ + +#include <math.h> +#include <stdint.h> + +namespace ros { + + void normalizeSecNSecSigned(int32_t& sec, int32_t& nsec); + + class Duration + { + public: + int32_t sec, nsec; + + Duration() : sec(0), nsec(0) {} + Duration(int32_t _sec, int32_t _nsec) : sec(_sec), nsec(_nsec) + { + normalizeSecNSecSigned(sec, nsec); + } + + double round(double number) { return number < 0.0 ? ceil(number - 0.5): floor(number + 0.5); } + double toSec() const { return (double)sec + 1e-9*(double)nsec; }; + void fromSec(double t) { sec = (uint32_t) floor(t); nsec = (uint32_t) round((t-sec) * 1e9); }; + + Duration& operator+=(const Duration &rhs); + Duration& operator-=(const Duration &rhs); + Duration& operator*=(double scale); + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/exception.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSLIB_EXCEPTION_H +#define ROSLIB_EXCEPTION_H + +#include <stdexcept> + +namespace ros +{ + +/** + * \brief Base class for all exceptions thrown by ROS + */ +class Exception : public std::runtime_error +{ +public: + Exception(const std::string& what) + : std::runtime_error(what) + {} +}; + +} // namespace ros + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/macros.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,66 @@ +/* + * Copyright (C) 2010, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSLIB_MACROS_H_INCLUDED +#define ROSLIB_MACROS_H_INCLUDED + +#if defined(__GNUC__) +#define ROS_DEPRECATED __attribute__((deprecated)) +#define ROS_FORCE_INLINE __attribute__((always_inline)) +#elif defined(_MSC_VER) +#define ROS_DEPRECATED +#define ROS_FORCE_INLINE __forceinline +#else +#define ROS_DEPRECATED +#define ROS_FORCE_INLINE inline +#endif + +/* + Windows import/export and gnu http://gcc.gnu.org/wiki/Visibility + macros. + */ +#if defined(_MSC_VER) + #define ROS_HELPER_IMPORT __declspec(dllimport) + #define ROS_HELPER_EXPORT __declspec(dllexport) + #define ROS_HELPER_LOCAL +#elif __GNUC__ >= 4 + #define ROS_HELPER_IMPORT __attribute__ ((visibility("default"))) + #define ROS_HELPER_EXPORT __attribute__ ((visibility("default"))) + #define ROS_HELPER_LOCAL __attribute__ ((visibility("hidden"))) +#else + #define ROS_HELPER_IMPORT + #define ROS_HELPER_EXPORT + #define ROS_HELPER_LOCAL +#endif + +// Ignore warnings about import/exports when deriving from std classes. +#ifdef _MSC_VER + #pragma warning(disable: 4251) + #pragma warning(disable: 4275) +#endif + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/message_forward.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,70 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSLIB_MESSAGE_FORWARD_H +#define ROSLIB_MESSAGE_FORWARD_H + +// Make sure that either __GLIBCXX__ or _LIBCPP_VERSION is defined. +#include <cstddef> + +// C++ standard section 17.4.3.1/1 states that forward declarations of STL types +// that aren't specializations involving user defined types results in undefined +// behavior. Apparently only libc++ has a problem with this and won't compile it. +#ifndef _LIBCPP_VERSION +namespace std +{ +template<typename T> class allocator; +} +#else +#include <memory> +#endif + +namespace boost +{ +template<typename T> class shared_ptr; +} + +/** + * \brief Forward-declare a message, including Ptr and ConstPtr types, with an allocator + * + * \param msg The "base" message type, i.e., the name of the .msg file + * \param new_name The name you'd like the message to have + * \param alloc The allocator to use, e.g. std::allocator + */ +#define ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(msg, new_name, alloc) \ + template<class Allocator> struct msg##_; \ + typedef msg##_<alloc<void> > new_name; \ + typedef boost::shared_ptr<new_name> new_name##Ptr; \ + typedef boost::shared_ptr<new_name const> new_name##ConstPtr; + +/** + * \brief Forward-declare a message, including Ptr and ConstPtr types, using std::allocator + * \param msg The "base" message type, i.e. the name of the .msg file + */ +#define ROS_DECLARE_MESSAGE(msg) ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(msg, msg, std::allocator) + +#endif // ROSLIB_MESSAGE_FORWARD_H \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/message_operations.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,76 @@ +/* + * Copyright (C) 2010, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSLIB_MESSAGE_OPERATIONS_H +#define ROSLIB_MESSAGE_OPERATIONS_H + +#include <ostream> + +namespace ros +{ +namespace message_operations +{ + +template<typename M> +struct Printer +{ + template<typename Stream> + static void stream(Stream& s, const std::string& indent, const M& value) + { + (void)indent; + s << value << "\n"; + } +}; + +// Explicitly specialize for uint8_t/int8_t because otherwise it thinks it's a char, and treats +// the value as a character code +template<> +struct Printer<int8_t> +{ + template<typename Stream> + static void stream(Stream& s, const std::string& indent, int8_t value) + { + (void)indent; + s << static_cast<int32_t>(value) << "\n"; + } +}; + +template<> +struct Printer<uint8_t> +{ + template<typename Stream> + static void stream(Stream& s, const std::string& indent, uint8_t value) + { + (void)indent; + s << static_cast<uint32_t>(value) << "\n"; + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // ROSLIB_MESSAGE_OPERATIONS_H
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/message_traits.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,360 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSLIB_MESSAGE_TRAITS_H +#define ROSLIB_MESSAGE_TRAITS_H + +#include "message_forward.h" + +#include <ros/time.h> + +#include <string> +#include <boost/utility/enable_if.hpp> +#include <boost/type_traits/remove_const.hpp> +#include <boost/type_traits/remove_reference.hpp> + +namespace std_msgs +{ + ROS_DECLARE_MESSAGE(Header) +} + +#define ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(msg, md5sum, datatype, definition) \ + namespace ros \ + { \ + namespace message_traits \ + { \ + template<> struct MD5Sum<msg> \ + { \ + static const char* value() { return md5sum; } \ + static const char* value(const msg&) { return value(); } \ + }; \ + template<> struct DataType<msg> \ + { \ + static const char* value() { return datatype; } \ + static const char* value(const msg&) { return value(); } \ + }; \ + template<> struct Definition<msg> \ + { \ + static const char* value() { return definition; } \ + static const char* value(const msg&) { return value(); } \ + }; \ + } \ + } + + +namespace ros +{ +namespace message_traits +{ + +/** + * \brief Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this type + * are \b true values. + */ +struct TrueType +{ + static const bool value = true; + typedef TrueType type; +}; + +/** + * \brief Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this type + * are \b false values. + */ +struct FalseType +{ + static const bool value = false; + typedef FalseType type; +}; + +/** + * \brief A simple datatype is one that can be memcpy'd directly in array form, i.e. it's a POD, fixed-size type and + * sizeof(M) == sum(serializationLength(M:a...)) + */ +template<typename M> struct IsSimple : public FalseType {}; +/** + * \brief A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings + */ +template<typename M> struct IsFixedSize : public FalseType {}; +/** + * \brief HasHeader informs whether or not there is a header that gets serialized as the first thing in the message + */ +template<typename M> struct HasHeader : public FalseType {}; + +/** + * \brief Am I message or not + */ +template<typename M> struct IsMessage : public FalseType {}; + +/** + * \brief Specialize to provide the md5sum for a message + */ +template<typename M> +struct MD5Sum +{ + static const char* value() + { + return M::__s_getMD5Sum().c_str(); + } + + static const char* value(const M& m) + { + return m.__getMD5Sum().c_str(); + } +}; + +/** + * \brief Specialize to provide the datatype for a message + */ +template<typename M> +struct DataType +{ + static const char* value() + { + return M::__s_getDataType().c_str(); + } + + static const char* value(const M& m) + { + return m.__getDataType().c_str(); + } +}; + +/** + * \brief Specialize to provide the definition for a message + */ +template<typename M> +struct Definition +{ + static const char* value() + { + return M::__s_getMessageDefinition().c_str(); + } + + static const char* value(const M& m) + { + return m.__getMessageDefinition().c_str(); + } +}; + +/** + * \brief Header trait. In the default implementation pointer() + * returns &m.header if HasHeader<M>::value is true, otherwise returns NULL + */ +template<typename M, typename Enable = void> +struct Header +{ + static std_msgs::Header* pointer(M& m) { (void)m; return 0; } + static std_msgs::Header const* pointer(const M& m) { (void)m; return 0; } +}; + +template<typename M> +struct Header<M, typename boost::enable_if<HasHeader<M> >::type > +{ + static std_msgs::Header* pointer(M& m) { return &m.header; } + static std_msgs::Header const* pointer(const M& m) { return &m.header; } +}; + +/** + * \brief FrameId trait. In the default implementation pointer() + * returns &m.header.frame_id if HasHeader<M>::value is true, otherwise returns NULL. value() + * does not exist, and causes a compile error + */ +template<typename M, typename Enable = void> +struct FrameId +{ + static std::string* pointer(M& m) { (void)m; return 0; } + static std::string const* pointer(const M& m) { (void)m; return 0; } +}; + +template<typename M> +struct FrameId<M, typename boost::enable_if<HasHeader<M> >::type > +{ + static std::string* pointer(M& m) { return &m.header.frame_id; } + static std::string const* pointer(const M& m) { return &m.header.frame_id; } + static std::string value(const M& m) { return m.header.frame_id; } +}; + +/** + * \brief TimeStamp trait. In the default implementation pointer() + * returns &m.header.stamp if HasHeader<M>::value is true, otherwise returns NULL. value() + * does not exist, and causes a compile error + */ +template<typename M, typename Enable = void> +struct TimeStamp +{ + static ros::Time* pointer(M& m) { (void)m; return 0; } + static ros::Time const* pointer(const M& m) { (void)m; return 0; } +}; + +template<typename M> +struct TimeStamp<M, typename boost::enable_if<HasHeader<M> >::type > +{ + static ros::Time* pointer(typename boost::remove_const<M>::type &m) { return &m.header.stamp; } + static ros::Time const* pointer(const M& m) { return &m.header.stamp; } + static ros::Time value(const M& m) { return m.header.stamp; } +}; + +/** + * \brief returns MD5Sum<M>::value(); + */ +template<typename M> +inline const char* md5sum() +{ + return MD5Sum<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value(); +} + +/** + * \brief returns DataType<M>::value(); + */ +template<typename M> +inline const char* datatype() +{ + return DataType<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value(); +} + +/** + * \brief returns Definition<M>::value(); + */ +template<typename M> +inline const char* definition() +{ + return Definition<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value(); +} + +/** + * \brief returns MD5Sum<M>::value(m); + */ +template<typename M> +inline const char* md5sum(const M& m) +{ + return MD5Sum<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value(m); +} + +/** + * \brief returns DataType<M>::value(m); + */ +template<typename M> +inline const char* datatype(const M& m) +{ + return DataType<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value(m); +} + +/** + * \brief returns Definition<M>::value(m); + */ +template<typename M> +inline const char* definition(const M& m) +{ + return Definition<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value(m); +} + +/** + * \brief returns Header<M>::pointer(m); + */ +template<typename M> +inline std_msgs::Header* header(M& m) +{ + return Header<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::pointer(m); +} + +/** + * \brief returns Header<M>::pointer(m); + */ +template<typename M> +inline std_msgs::Header const* header(const M& m) +{ + return Header<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::pointer(m); +} + +/** + * \brief returns FrameId<M>::pointer(m); + */ +template<typename M> +inline std::string* frameId(M& m) +{ + return FrameId<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::pointer(m); +} + +/** + * \brief returns FrameId<M>::pointer(m); + */ +template<typename M> +inline std::string const* frameId(const M& m) +{ + return FrameId<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::pointer(m); +} + +/** + * \brief returns TimeStamp<M>::pointer(m); + */ +template<typename M> +inline ros::Time* timeStamp(M& m) +{ + return TimeStamp<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::pointer(m); +} + +/** + * \brief returns TimeStamp<M>::pointer(m); + */ +template<typename M> +inline ros::Time const* timeStamp(const M& m) +{ + return TimeStamp<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::pointer(m); +} + +/** + * \brief returns IsSimple<M>::value; + */ +template<typename M> +inline bool isSimple() +{ + return IsSimple<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value; +} + +/** + * \brief returns IsFixedSize<M>::value; + */ +template<typename M> +inline bool isFixedSize() +{ + return IsFixedSize<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value; +} + +/** + * \brief returns HasHeader<M>::value; + */ +template<typename M> +inline bool hasHeader() +{ + return HasHeader<typename boost::remove_reference<typename boost::remove_const<M>::type>::type>::value; +} + +} // namespace message_traits +} // namespace ros + +#endif // ROSLIB_MESSAGE_TRAITS_H \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/msg.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,147 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_MSG_H_ +#define _ROS_MSG_H_ + +#include <stdint.h> +#include <stddef.h> + +namespace ros { + +/* Base Message Type */ +class Msg +{ +public: + virtual int serialize(unsigned char *outbuffer) const = 0; + virtual int deserialize(unsigned char *data) = 0; + virtual const char * getType() = 0; + virtual const char * getMD5() = 0; + + /** + * @brief This tricky function handles promoting a 32bit float to a 64bit + * double, so that AVR can publish messages containing float64 + * fields, despite AVV having no native support for double. + * + * @param[out] outbuffer pointer for buffer to serialize to. + * @param[in] f value to serialize. + * + * @return number of bytes to advance the buffer pointer. + * + */ + static int serializeAvrFloat64(unsigned char* outbuffer, const float f) + { + const int32_t* val = (int32_t*) &f; + int32_t exp = ((*val >> 23) & 255); + if (exp != 0) + { + exp += 1023 - 127; + } + + int32_t sig = *val; + *(outbuffer++) = 0; + *(outbuffer++) = 0; + *(outbuffer++) = 0; + *(outbuffer++) = (sig << 5) & 0xff; + *(outbuffer++) = (sig >> 3) & 0xff; + *(outbuffer++) = (sig >> 11) & 0xff; + *(outbuffer++) = ((exp << 4) & 0xF0) | ((sig >> 19) & 0x0F); + *(outbuffer++) = (exp >> 4) & 0x7F; + + // Mark negative bit as necessary. + if (f < 0) + { + *(outbuffer - 1) |= 0x80; + } + + return 8; + } + + /** + * @brief This tricky function handles demoting a 64bit double to a + * 32bit float, so that AVR can understand messages containing + * float64 fields, despite AVR having no native support for double. + * + * @param[in] inbuffer pointer for buffer to deserialize from. + * @param[out] f pointer to place the deserialized value in. + * + * @return number of bytes to advance the buffer pointer. + */ + static int deserializeAvrFloat64(const unsigned char* inbuffer, float* f) + { + uint32_t* val = (uint32_t*)f; + inbuffer += 3; + + // Copy truncated mantissa. + *val = ((uint32_t)(*(inbuffer++)) >> 5 & 0x07); + *val |= ((uint32_t)(*(inbuffer++)) & 0xff) << 3; + *val |= ((uint32_t)(*(inbuffer++)) & 0xff) << 11; + *val |= ((uint32_t)(*inbuffer) & 0x0f) << 19; + + // Copy truncated exponent. + uint32_t exp = ((uint32_t)(*(inbuffer++)) & 0xf0)>>4; + exp |= ((uint32_t)(*inbuffer) & 0x7f) << 4; + if (exp != 0) + { + *val |= ((exp) - 1023 + 127) << 23; + } + + // Copy negative sign. + *val |= ((uint32_t)(*(inbuffer++)) & 0x80) << 24; + + return 8; + } + + // Copy data from variable into a byte array + template<typename A, typename V> + static void varToArr(A arr, const V var) + { + for(size_t i = 0; i < sizeof(V); i++) + arr[i] = (var >> (8 * i)); + } + + // Copy data from a byte array into variable + template<typename V, typename A> + static void arrToVar(V& var, const A arr) + { + var = 0; + for(size_t i = 0; i < sizeof(V); i++) + var |= (arr[i] << (8 * i)); + } + +}; + +} // namespace ros + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/node_handle.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,543 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_NODE_HANDLE_H_ +#define ROS_NODE_HANDLE_H_ + +#include <stdint.h> + +#include "std_msgs/Time.h" +#include "rosserial_msgs/TopicInfo.h" +#include "rosserial_msgs/Log.h" +#include "rosserial_msgs/RequestParam.h" + +#define SYNC_SECONDS 5 + +#define MODE_FIRST_FF 0 +/* + * The second sync byte is a protocol version. It's value is 0xff for the first + * version of the rosserial protocol (used up to hydro), 0xfe for the second version + * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable + * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy + * rosserial_arduino. It must be changed in both this file and in + * rosserial_python/src/rosserial_python/SerialClient.py + */ +#define MODE_PROTOCOL_VER 1 +#define PROTOCOL_VER1 0xff // through groovy +#define PROTOCOL_VER2 0xfe // in hydro +#define PROTOCOL_VER PROTOCOL_VER2 +#define MODE_SIZE_L 2 +#define MODE_SIZE_H 3 +#define MODE_SIZE_CHECKSUM 4 // checksum for msg size received from size L and H +#define MODE_TOPIC_L 5 // waiting for topic id +#define MODE_TOPIC_H 6 +#define MODE_MESSAGE 7 +#define MODE_MSG_CHECKSUM 8 // checksum for msg and topic id + + +#define MSG_TIMEOUT 20 //20 milliseconds to recieve all of message data + +#include "ros/msg.h" + +namespace ros { + + class NodeHandleBase_{ + public: + virtual int publish(int id, const Msg* msg)=0; + virtual int spinOnce()=0; + virtual bool connected()=0; + }; +} + +#include "ros/publisher.h" +#include "ros/subscriber.h" +#include "ros/service_server.h" +#include "ros/service_client.h" + +namespace ros { + + using rosserial_msgs::TopicInfo; + + /* Node Handle */ + template<class Hardware, + int MAX_SUBSCRIBERS=25, + int MAX_PUBLISHERS=25, + int INPUT_SIZE=512, + int OUTPUT_SIZE=512> + class NodeHandle_ : public NodeHandleBase_ + { + protected: + Hardware hardware_; + + /* time used for syncing */ + uint32_t rt_time; + + /* used for computing current time */ + uint32_t sec_offset, nsec_offset; + + uint8_t message_in[INPUT_SIZE]; + uint8_t message_out[OUTPUT_SIZE]; + + Publisher * publishers[MAX_PUBLISHERS]; + Subscriber_ * subscribers[MAX_SUBSCRIBERS]; + + /* + * Setup Functions + */ + public: + NodeHandle_() : configured_(false) { + + for(unsigned int i=0; i< MAX_PUBLISHERS; i++) + publishers[i] = 0; + + for(unsigned int i=0; i< MAX_SUBSCRIBERS; i++) + subscribers[i] = 0; + + for(unsigned int i=0; i< INPUT_SIZE; i++) + message_in[i] = 0; + + for(unsigned int i=0; i< OUTPUT_SIZE; i++) + message_out[i] = 0; + + req_param_resp.ints_length = 0; + req_param_resp.ints = NULL; + req_param_resp.floats_length = 0; + req_param_resp.floats = NULL; + req_param_resp.ints_length = 0; + req_param_resp.ints = NULL; + } + + Hardware* getHardware(){ + return &hardware_; + } + + /* Start serial, initialize buffers */ + void initNode(){ + hardware_.init(); + mode_ = 0; + bytes_ = 0; + index_ = 0; + topic_ = 0; + }; + + /* Start a named port, which may be network server IP, initialize buffers */ + void initNode(char *portName){ + hardware_.init(portName); + mode_ = 0; + bytes_ = 0; + index_ = 0; + topic_ = 0; + }; + + protected: + //State machine variables for spinOnce + int mode_; + int bytes_; + int topic_; + int index_; + int checksum_; + + bool configured_; + + /* used for syncing the time */ + uint32_t last_sync_time; + uint32_t last_sync_receive_time; + uint32_t last_msg_timeout_time; + + public: + /* This function goes in your loop() function, it handles + * serial input and callbacks for subscribers. + */ + + + virtual int spinOnce(){ + + /* restart if timed out */ + uint32_t c_time = hardware_.time(); + if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){ + configured_ = false; + } + + /* reset if message has timed out */ + if ( mode_ != MODE_FIRST_FF){ + if (c_time > last_msg_timeout_time){ + mode_ = MODE_FIRST_FF; + } + } + + /* while available buffer, read data */ + while( true ) + { + int data = hardware_.read(); + if( data < 0 ) + break; + checksum_ += data; + if( mode_ == MODE_MESSAGE ){ /* message data being recieved */ + message_in[index_++] = data; + bytes_--; + if(bytes_ == 0) /* is message complete? if so, checksum */ + mode_ = MODE_MSG_CHECKSUM; + }else if( mode_ == MODE_FIRST_FF ){ + if(data == 0xff){ + mode_++; + last_msg_timeout_time = c_time + MSG_TIMEOUT; + } + else if( hardware_.time() - c_time > (SYNC_SECONDS)){ + /* We have been stuck in spinOnce too long, return error */ + configured_=false; + return -2; + } + }else if( mode_ == MODE_PROTOCOL_VER ){ + if(data == PROTOCOL_VER){ + mode_++; + }else{ + mode_ = MODE_FIRST_FF; + if (configured_ == false) + requestSyncTime(); /* send a msg back showing our protocol version */ + } + }else if( mode_ == MODE_SIZE_L ){ /* bottom half of message size */ + bytes_ = data; + index_ = 0; + mode_++; + checksum_ = data; /* first byte for calculating size checksum */ + }else if( mode_ == MODE_SIZE_H ){ /* top half of message size */ + bytes_ += data<<8; + mode_++; + }else if( mode_ == MODE_SIZE_CHECKSUM ){ + if( (checksum_%256) == 255) + mode_++; + else + mode_ = MODE_FIRST_FF; /* Abandon the frame if the msg len is wrong */ + }else if( mode_ == MODE_TOPIC_L ){ /* bottom half of topic id */ + topic_ = data; + mode_++; + checksum_ = data; /* first byte included in checksum */ + }else if( mode_ == MODE_TOPIC_H ){ /* top half of topic id */ + topic_ += data<<8; + mode_ = MODE_MESSAGE; + if(bytes_ == 0) + mode_ = MODE_MSG_CHECKSUM; + }else if( mode_ == MODE_MSG_CHECKSUM ){ /* do checksum */ + mode_ = MODE_FIRST_FF; + if( (checksum_%256) == 255){ + if(topic_ == TopicInfo::ID_PUBLISHER){ + requestSyncTime(); + negotiateTopics(); + last_sync_time = c_time; + last_sync_receive_time = c_time; + return -1; + }else if(topic_ == TopicInfo::ID_TIME){ + syncTime(message_in); + }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){ + req_param_resp.deserialize(message_in); + param_recieved= true; + }else if(topic_ == TopicInfo::ID_TX_STOP){ + configured_ = false; + }else{ + if(subscribers[topic_-100]) + subscribers[topic_-100]->callback( message_in ); + } + } + } + } + + /* occasionally sync time */ + if( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){ + requestSyncTime(); + last_sync_time = c_time; + } + + return 0; + } + + + /* Are we connected to the PC? */ + virtual bool connected() { + return configured_; + }; + + /******************************************************************** + * Time functions + */ + + void requestSyncTime() + { + std_msgs::Time t; + publish(TopicInfo::ID_TIME, &t); + rt_time = hardware_.time(); + } + + void syncTime(uint8_t * data) + { + std_msgs::Time t; + uint32_t offset = hardware_.time() - rt_time; + + t.deserialize(data); + t.data.sec += offset/1000; + t.data.nsec += (offset%1000)*1000000UL; + + this->setNow(t.data); + last_sync_receive_time = hardware_.time(); + } + + Time now() + { + uint32_t ms = hardware_.time(); + Time current_time; + current_time.sec = ms/1000 + sec_offset; + current_time.nsec = (ms%1000)*1000000UL + nsec_offset; + normalizeSecNSec(current_time.sec, current_time.nsec); + return current_time; + } + + void setNow( Time & new_now ) + { + uint32_t ms = hardware_.time(); + sec_offset = new_now.sec - ms/1000 - 1; + nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL; + normalizeSecNSec(sec_offset, nsec_offset); + } + + /******************************************************************** + * Topic Management + */ + + /* Register a new publisher */ + bool advertise(Publisher & p) + { + for(int i = 0; i < MAX_PUBLISHERS; i++){ + if(publishers[i] == 0){ // empty slot + publishers[i] = &p; + p.id_ = i+100+MAX_SUBSCRIBERS; + p.nh_ = this; + return true; + } + } + return false; + } + + /* Register a new subscriber */ + template<typename SubscriberT> + bool subscribe(SubscriberT& s){ + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = static_cast<Subscriber_*>(&s); + s.id_ = i+100; + return true; + } + } + return false; + } + + /* Register a new Service Server */ + template<typename MReq, typename MRes> + bool advertiseService(ServiceServer<MReq,MRes>& srv){ + bool v = advertise(srv.pub); + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = static_cast<Subscriber_*>(&srv); + srv.id_ = i+100; + return v; + } + } + return false; + } + + /* Register a new Service Client */ + template<typename MReq, typename MRes> + bool serviceClient(ServiceClient<MReq, MRes>& srv){ + bool v = advertise(srv.pub); + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = static_cast<Subscriber_*>(&srv); + srv.id_ = i+100; + return v; + } + } + return false; + } + + void negotiateTopics() + { + rosserial_msgs::TopicInfo ti; + int i; + for(i = 0; i < MAX_PUBLISHERS; i++) + { + if(publishers[i] != 0) // non-empty slot + { + ti.topic_id = publishers[i]->id_; + ti.topic_name = (char *) publishers[i]->topic_; + ti.message_type = (char *) publishers[i]->msg_->getType(); + ti.md5sum = (char *) publishers[i]->msg_->getMD5(); + ti.buffer_size = OUTPUT_SIZE; + publish( publishers[i]->getEndpointType(), &ti ); + } + } + for(i = 0; i < MAX_SUBSCRIBERS; i++) + { + if(subscribers[i] != 0) // non-empty slot + { + ti.topic_id = subscribers[i]->id_; + ti.topic_name = (char *) subscribers[i]->topic_; + ti.message_type = (char *) subscribers[i]->getMsgType(); + ti.md5sum = (char *) subscribers[i]->getMsgMD5(); + ti.buffer_size = INPUT_SIZE; + publish( subscribers[i]->getEndpointType(), &ti ); + } + } + configured_ = true; + } + + virtual int publish(int id, const Msg * msg) + { + if(id >= 100 && !configured_) + return 0; + + /* serialize message */ + uint16_t l = msg->serialize(message_out+7); + + /* setup the header */ + message_out[0] = 0xff; + message_out[1] = PROTOCOL_VER; + message_out[2] = (uint8_t) ((uint16_t)l&255); + message_out[3] = (uint8_t) ((uint16_t)l>>8); + message_out[4] = 255 - ((message_out[2] + message_out[3])%256); + message_out[5] = (uint8_t) ((int16_t)id&255); + message_out[6] = (uint8_t) ((int16_t)id>>8); + + /* calculate checksum */ + int chk = 0; + for(int i =5; i<l+7; i++) + chk += message_out[i]; + l += 7; + message_out[l++] = 255 - (chk%256); + + if( l <= OUTPUT_SIZE ){ + hardware_.write(message_out, l); + return l; + }else{ + logerror("Message from device dropped: message larger than buffer."); + return -1; + } + } + + /******************************************************************** + * Logging + */ + + private: + void log(char byte, const char * msg){ + rosserial_msgs::Log l; + l.level= byte; + l.msg = (char*)msg; + publish(rosserial_msgs::TopicInfo::ID_LOG, &l); + } + + public: + void logdebug(const char* msg){ + log(rosserial_msgs::Log::ROSDEBUG, msg); + } + void loginfo(const char * msg){ + log(rosserial_msgs::Log::INFO, msg); + } + void logwarn(const char *msg){ + log(rosserial_msgs::Log::WARN, msg); + } + void logerror(const char*msg){ + log(rosserial_msgs::Log::ERROR, msg); + } + void logfatal(const char*msg){ + log(rosserial_msgs::Log::FATAL, msg); + } + + /******************************************************************** + * Parameters + */ + + private: + bool param_recieved; + rosserial_msgs::RequestParamResponse req_param_resp; + + bool requestParam(const char * name, int time_out = 1000){ + param_recieved = false; + rosserial_msgs::RequestParamRequest req; + req.name = (char*)name; + publish(TopicInfo::ID_PARAMETER_REQUEST, &req); + uint16_t end_time = hardware_.time() + time_out; + while(!param_recieved ){ + spinOnce(); + if (hardware_.time() > end_time) return false; + } + return true; + } + + public: + bool getParam(const char* name, int* param, int length =1){ + if (requestParam(name) ){ + if (length == req_param_resp.ints_length){ + //copy it over + for(int i=0; i<length; i++) + param[i] = req_param_resp.ints[i]; + return true; + } + } + return false; + } + bool getParam(const char* name, float* param, int length=1){ + if (requestParam(name) ){ + if (length == req_param_resp.floats_length){ + //copy it over + for(int i=0; i<length; i++) + param[i] = req_param_resp.floats[i]; + return true; + } + } + return false; + } + bool getParam(const char* name, char** param, int length=1){ + if (requestParam(name) ){ + if (length == req_param_resp.strings_length){ + //copy it over + for(int i=0; i<length; i++) + strcpy(param[i],req_param_resp.strings[i]); + return true; + } + } + return false; + } + }; + +} + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/publisher.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,67 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_PUBLISHER_H_ +#define _ROS_PUBLISHER_H_ + +#include "rosserial_msgs/TopicInfo.h" +#include "ros/node_handle.h" + +namespace ros { + + /* Generic Publisher */ + class Publisher + { + public: + Publisher( const char * topic_name, Msg * msg, int endpoint=rosserial_msgs::TopicInfo::ID_PUBLISHER) : + topic_(topic_name), + msg_(msg), + endpoint_(endpoint) {}; + + int publish( const Msg * msg ) { return nh_->publish(id_, msg); }; + int getEndpointType(){ return endpoint_; } + + const char * topic_; + Msg *msg_; + // id_ and no_ are set by NodeHandle when we advertise + int id_; + NodeHandleBase_* nh_; + + private: + int endpoint_; + }; + +} + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/roscpp_serialization_macros.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,55 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*********************************************************************/ +/* + * Cross platform macros. + * + */ +#ifndef ROSCPP_SERIALIZATION_MACROS_HPP_ +#define ROSCPP_SERIALIZATION_MACROS_HPP_ + +#include <ros/macros.h> + +#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries + #ifdef roscpp_serialization_EXPORTS // we are building a shared lib/dll + #define ROSCPP_SERIALIZATION_DECL ROS_HELPER_EXPORT + #else // we are using shared lib/dll + #define ROSCPP_SERIALIZATION_DECL ROS_HELPER_IMPORT + #endif +#else // ros is being built around static libraries + #define ROSCPP_SERIALIZATION_DECL +#endif + +#endif /* ROSCPP_SERIALIZATION_MACROS_HPP_ */ \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/serialization.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,887 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSCPP_SERIALIZATION_H +#define ROSCPP_SERIALIZATION_H + +#include "roscpp_serialization_macros.h" + +#include <ros/types.h> +#include <ros/time.h> + +#include "serialized_message.h" +#include "ros/message_traits.h" +#include "ros/builtin_message_traits.h" +#include "ros/exception.h" +#include "ros/datatypes.h" + +#include <vector> +#include <map> + +#include <boost/array.hpp> +#include <boost/call_traits.hpp> +#include <boost/utility/enable_if.hpp> +#include <boost/mpl/and.hpp> +#include <boost/mpl/or.hpp> +#include <boost/mpl/not.hpp> + +#include <cstring> + +#define ROS_NEW_SERIALIZATION_API 1 + +/** + * \brief Declare your serializer to use an allInOne member instead of requiring 3 different serialization + * functions. + * + * The allinone method has the form: +\verbatim +template<typename Stream, typename T> +inline static void allInOne(Stream& stream, T t) +{ + stream.next(t.a); + stream.next(t.b); + ... +} +\endverbatim + * + * The only guarantee given is that Stream::next(T) is defined. + */ +#define ROS_DECLARE_ALLINONE_SERIALIZER \ + template<typename Stream, typename T> \ + inline static void write(Stream& stream, const T& t) \ + { \ + allInOne<Stream, const T&>(stream, t); \ + } \ + \ + template<typename Stream, typename T> \ + inline static void read(Stream& stream, T& t) \ + { \ + allInOne<Stream, T&>(stream, t); \ + } \ + \ + template<typename T> \ + inline static uint32_t serializedLength(const T& t) \ + { \ + LStream stream; \ + allInOne<LStream, const T&>(stream, t); \ + return stream.getLength(); \ + } + +namespace ros +{ +namespace serialization +{ +namespace mt = message_traits; +namespace mpl = boost::mpl; + +class ROSCPP_SERIALIZATION_DECL StreamOverrunException : public ros::Exception +{ +public: + StreamOverrunException(const std::string& what) + : Exception(what) + {} +}; + +ROSCPP_SERIALIZATION_DECL void throwStreamOverrun(); + +/** + * \brief Templated serialization class. Default implementation provides backwards compatibility with + * old message types. + * + * Specializing the Serializer class is the only thing you need to do to get the ROS serialization system + * to work with a type. + */ +template<typename T> +struct Serializer +{ + /** + * \brief Write an object to the stream. Normally the stream passed in here will be a ros::serialization::OStream + */ + template<typename Stream> + inline static void write(Stream& stream, typename boost::call_traits<T>::param_type t) + { + t.serialize(stream.getData(), 0); + } + + /** + * \brief Read an object from the stream. Normally the stream passed in here will be a ros::serialization::IStream + */ + template<typename Stream> + inline static void read(Stream& stream, typename boost::call_traits<T>::reference t) + { + t.deserialize(stream.getData()); + } + + /** + * \brief Determine the serialized length of an object. + */ + inline static uint32_t serializedLength(typename boost::call_traits<T>::param_type t) + { + return t.serializationLength(); + } +}; + +/** + * \brief Serialize an object. Stream here should normally be a ros::serialization::OStream + */ +template<typename T, typename Stream> +inline void serialize(Stream& stream, const T& t) +{ + Serializer<T>::write(stream, t); +} + +/** + * \brief Deserialize an object. Stream here should normally be a ros::serialization::IStream + */ +template<typename T, typename Stream> +inline void deserialize(Stream& stream, T& t) +{ + Serializer<T>::read(stream, t); +} + +/** + * \brief Determine the serialized length of an object + */ +template<typename T> +inline uint32_t serializationLength(const T& t) +{ + return Serializer<T>::serializedLength(t); +} + +#define ROS_CREATE_SIMPLE_SERIALIZER(Type) \ + template<> struct Serializer<Type> \ + { \ + template<typename Stream> inline static void write(Stream& stream, const Type v) \ + { \ + memcpy(stream.advance(sizeof(v)), &v, sizeof(v) ); \ + } \ + \ + template<typename Stream> inline static void read(Stream& stream, Type& v) \ + { \ + memcpy(&v, stream.advance(sizeof(v)), sizeof(v) ); \ + } \ + \ + inline static uint32_t serializedLength(const Type&) \ + { \ + return sizeof(Type); \ + } \ +}; + +ROS_CREATE_SIMPLE_SERIALIZER(uint8_t) +ROS_CREATE_SIMPLE_SERIALIZER(int8_t) +ROS_CREATE_SIMPLE_SERIALIZER(uint16_t) +ROS_CREATE_SIMPLE_SERIALIZER(int16_t) +ROS_CREATE_SIMPLE_SERIALIZER(uint32_t) +ROS_CREATE_SIMPLE_SERIALIZER(int32_t) +ROS_CREATE_SIMPLE_SERIALIZER(uint64_t) +ROS_CREATE_SIMPLE_SERIALIZER(int64_t) +ROS_CREATE_SIMPLE_SERIALIZER(float) +ROS_CREATE_SIMPLE_SERIALIZER(double) + +/** + * \brief Serializer specialized for bool (serialized as uint8) + */ +template<> struct Serializer<bool> +{ + template<typename Stream> inline static void write(Stream& stream, const bool v) + { + uint8_t b = (uint8_t)v; + memcpy(stream.advance(1), &b, 1 ); + } + + template<typename Stream> inline static void read(Stream& stream, bool& v) + { + uint8_t b; + memcpy(&b, stream.advance(1), 1 ); + v = (bool)b; + } + + inline static uint32_t serializedLength(bool) + { + return 1; + } +}; + +/** + * \brief Serializer specialized for std::string + */ +template<class ContainerAllocator> +struct Serializer<std::basic_string<char, std::char_traits<char>, ContainerAllocator> > +{ + typedef std::basic_string<char, std::char_traits<char>, ContainerAllocator> StringType; + + template<typename Stream> + inline static void write(Stream& stream, const StringType& str) + { + size_t len = str.size(); + stream.next((uint32_t)len); + + if (len > 0) + { + memcpy(stream.advance((uint32_t)len), str.data(), len); + } + } + + template<typename Stream> + inline static void read(Stream& stream, StringType& str) + { + uint32_t len; + stream.next(len); + if (len > 0) + { + str = StringType((char*)stream.advance(len), len); + } + else + { + str.clear(); + } + } + + inline static uint32_t serializedLength(const StringType& str) + { + return 4 + (uint32_t)str.size(); + } +}; + +/** + * \brief Serializer specialized for ros::Time + */ +template<> +struct Serializer<ros::Time> +{ + template<typename Stream> + inline static void write(Stream& stream, const ros::Time& v) + { + stream.next(v.sec); + stream.next(v.nsec); + } + + template<typename Stream> + inline static void read(Stream& stream, ros::Time& v) + { + stream.next(v.sec); + stream.next(v.nsec); + } + + inline static uint32_t serializedLength(const ros::Time&) + { + return 8; + } +}; + +/** + * \brief Serializer specialized for ros::Duration + */ +template<> +struct Serializer<ros::Duration> +{ + template<typename Stream> + inline static void write(Stream& stream, const ros::Duration& v) + { + stream.next(v.sec); + stream.next(v.nsec); + } + + template<typename Stream> + inline static void read(Stream& stream, ros::Duration& v) + { + stream.next(v.sec); + stream.next(v.nsec); + } + + inline static uint32_t serializedLength(const ros::Duration&) + { + return 8; + } +}; + +/** + * \brief Vector serializer. Default implementation does nothing + */ +template<typename T, class ContainerAllocator, class Enabled = void> +struct VectorSerializer +{}; + +/** + * \brief Vector serializer, specialized for non-fixed-size, non-simple types + */ +template<typename T, class ContainerAllocator> +struct VectorSerializer<T, ContainerAllocator, typename boost::disable_if<mt::IsFixedSize<T> >::type > +{ + typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType; + typedef typename VecType::iterator IteratorType; + typedef typename VecType::const_iterator ConstIteratorType; + + template<typename Stream> + inline static void write(Stream& stream, const VecType& v) + { + stream.next((uint32_t)v.size()); + ConstIteratorType it = v.begin(); + ConstIteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + template<typename Stream> + inline static void read(Stream& stream, VecType& v) + { + uint32_t len; + stream.next(len); + v.resize(len); + IteratorType it = v.begin(); + IteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + inline static uint32_t serializedLength(const VecType& v) + { + uint32_t size = 4; + ConstIteratorType it = v.begin(); + ConstIteratorType end = v.end(); + for (; it != end; ++it) + { + size += serializationLength(*it); + } + + return size; + } +}; + +/** + * \brief Vector serializer, specialized for fixed-size simple types + */ +template<typename T, class ContainerAllocator> +struct VectorSerializer<T, ContainerAllocator, typename boost::enable_if<mt::IsSimple<T> >::type > +{ + typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType; + typedef typename VecType::iterator IteratorType; + typedef typename VecType::const_iterator ConstIteratorType; + + template<typename Stream> + inline static void write(Stream& stream, const VecType& v) + { + uint32_t len = (uint32_t)v.size(); + stream.next(len); + if (!v.empty()) + { + const uint32_t data_len = len * (uint32_t)sizeof(T); + memcpy(stream.advance(data_len), &v.front(), data_len); + } + } + + template<typename Stream> + inline static void read(Stream& stream, VecType& v) + { + uint32_t len; + stream.next(len); + v.resize(len); + + if (len > 0) + { + const uint32_t data_len = (uint32_t)sizeof(T) * len; + memcpy(&v.front(), stream.advance(data_len), data_len); + } + } + + inline static uint32_t serializedLength(const VecType& v) + { + return 4 + v.size() * (uint32_t)sizeof(T); + } +}; + +/** + * \brief Vector serializer, specialized for fixed-size non-simple types + */ +template<typename T, class ContainerAllocator> +struct VectorSerializer<T, ContainerAllocator, typename boost::enable_if<mpl::and_<mt::IsFixedSize<T>, mpl::not_<mt::IsSimple<T> > > >::type > +{ + typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType; + typedef typename VecType::iterator IteratorType; + typedef typename VecType::const_iterator ConstIteratorType; + + template<typename Stream> + inline static void write(Stream& stream, const VecType& v) + { + stream.next((uint32_t)v.size()); + ConstIteratorType it = v.begin(); + ConstIteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + template<typename Stream> + inline static void read(Stream& stream, VecType& v) + { + uint32_t len; + stream.next(len); + v.resize(len); + IteratorType it = v.begin(); + IteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + inline static uint32_t serializedLength(const VecType& v) + { + uint32_t size = 4; + if (!v.empty()) + { + uint32_t len_each = serializationLength(v.front()); + size += len_each * (uint32_t)v.size(); + } + + return size; + } +}; + +/** + * \brief serialize version for std::vector + */ +template<typename T, class ContainerAllocator, typename Stream> +inline void serialize(Stream& stream, const std::vector<T, ContainerAllocator>& t) +{ + VectorSerializer<T, ContainerAllocator>::write(stream, t); +} + +/** + * \brief deserialize version for std::vector + */ +template<typename T, class ContainerAllocator, typename Stream> +inline void deserialize(Stream& stream, std::vector<T, ContainerAllocator>& t) +{ + VectorSerializer<T, ContainerAllocator>::read(stream, t); +} + +/** + * \brief serializationLength version for std::vector + */ +template<typename T, class ContainerAllocator> +inline uint32_t serializationLength(const std::vector<T, ContainerAllocator>& t) +{ + return VectorSerializer<T, ContainerAllocator>::serializedLength(t); +} + +/** + * \brief Array serializer, default implementation does nothing + */ +template<typename T, size_t N, class Enabled = void> +struct ArraySerializer +{}; + +/** + * \brief Array serializer, specialized for non-fixed-size, non-simple types + */ +template<typename T, size_t N> +struct ArraySerializer<T, N, typename boost::disable_if<mt::IsFixedSize<T> >::type> +{ + typedef boost::array<T, N > ArrayType; + typedef typename ArrayType::iterator IteratorType; + typedef typename ArrayType::const_iterator ConstIteratorType; + + template<typename Stream> + inline static void write(Stream& stream, const ArrayType& v) + { + ConstIteratorType it = v.begin(); + ConstIteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + template<typename Stream> + inline static void read(Stream& stream, ArrayType& v) + { + IteratorType it = v.begin(); + IteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + inline static uint32_t serializedLength(const ArrayType& v) + { + uint32_t size = 0; + ConstIteratorType it = v.begin(); + ConstIteratorType end = v.end(); + for (; it != end; ++it) + { + size += serializationLength(*it); + } + + return size; + } +}; + +/** + * \brief Array serializer, specialized for fixed-size, simple types + */ +template<typename T, size_t N> +struct ArraySerializer<T, N, typename boost::enable_if<mt::IsSimple<T> >::type> +{ + typedef boost::array<T, N > ArrayType; + typedef typename ArrayType::iterator IteratorType; + typedef typename ArrayType::const_iterator ConstIteratorType; + + template<typename Stream> + inline static void write(Stream& stream, const ArrayType& v) + { + const uint32_t data_len = N * sizeof(T); + memcpy(stream.advance(data_len), &v.front(), data_len); + } + + template<typename Stream> + inline static void read(Stream& stream, ArrayType& v) + { + const uint32_t data_len = N * sizeof(T); + memcpy(&v.front(), stream.advance(data_len), data_len); + } + + inline static uint32_t serializedLength(const ArrayType&) + { + return N * sizeof(T); + } +}; + +/** + * \brief Array serializer, specialized for fixed-size, non-simple types + */ +template<typename T, size_t N> +struct ArraySerializer<T, N, typename boost::enable_if<mpl::and_<mt::IsFixedSize<T>, mpl::not_<mt::IsSimple<T> > > >::type> +{ + typedef boost::array<T, N > ArrayType; + typedef typename ArrayType::iterator IteratorType; + typedef typename ArrayType::const_iterator ConstIteratorType; + + template<typename Stream> + inline static void write(Stream& stream, const ArrayType& v) + { + ConstIteratorType it = v.begin(); + ConstIteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + template<typename Stream> + inline static void read(Stream& stream, ArrayType& v) + { + IteratorType it = v.begin(); + IteratorType end = v.end(); + for (; it != end; ++it) + { + stream.next(*it); + } + } + + inline static uint32_t serializedLength(const ArrayType& v) + { + return serializationLength(v.front()) * N; + } +}; + +/** + * \brief serialize version for boost::array + */ +template<typename T, size_t N, typename Stream> +inline void serialize(Stream& stream, const boost::array<T, N>& t) +{ + ArraySerializer<T, N>::write(stream, t); +} + +/** + * \brief deserialize version for boost::array + */ +template<typename T, size_t N, typename Stream> +inline void deserialize(Stream& stream, boost::array<T, N>& t) +{ + ArraySerializer<T, N>::read(stream, t); +} + +/** + * \brief serializationLength version for boost::array + */ +template<typename T, size_t N> +inline uint32_t serializationLength(const boost::array<T, N>& t) +{ + return ArraySerializer<T, N>::serializedLength(t); +} + +/** + * \brief Enum + */ +namespace stream_types +{ +enum StreamType +{ + Input, + Output, + Length +}; +} +typedef stream_types::StreamType StreamType; + +/** + * \brief Stream base-class, provides common functionality for IStream and OStream + */ +struct ROSCPP_SERIALIZATION_DECL Stream +{ + /* + * \brief Returns a pointer to the current position of the stream + */ + inline uint8_t* getData() { return data_; } + /** + * \brief Advances the stream, checking bounds, and returns a pointer to the position before it + * was advanced. + * \throws StreamOverrunException if len would take this stream past the end of its buffer + */ + ROS_FORCE_INLINE uint8_t* advance(uint32_t len) + { + uint8_t* old_data = data_; + data_ += len; + if (data_ > end_) + { + // Throwing directly here causes a significant speed hit due to the extra code generated + // for the throw statement + throwStreamOverrun(); + } + return old_data; + } + + /** + * \brief Returns the amount of space left in the stream + */ + inline uint32_t getLength() { return (uint32_t)(end_ - data_); } + +protected: + Stream(uint8_t* _data, uint32_t _count) + : data_(_data) + , end_(_data + _count) + {} + +private: + uint8_t* data_; + uint8_t* end_; +}; + +/** + * \brief Input stream + */ +struct ROSCPP_SERIALIZATION_DECL IStream : public Stream +{ + static const StreamType stream_type = stream_types::Input; + + IStream(uint8_t* data, uint32_t count) + : Stream(data, count) + {} + + /** + * \brief Deserialize an item from this input stream + */ + template<typename T> + ROS_FORCE_INLINE void next(T& t) + { + deserialize(*this, t); + } + + template<typename T> + ROS_FORCE_INLINE IStream& operator>>(T& t) + { + deserialize(*this, t); + return *this; + } +}; + +/** + * \brief Output stream + */ +struct ROSCPP_SERIALIZATION_DECL OStream : public Stream +{ + static const StreamType stream_type = stream_types::Output; + + OStream(uint8_t* data, uint32_t count) + : Stream(data, count) + {} + + /** + * \brief Serialize an item to this output stream + */ + template<typename T> + ROS_FORCE_INLINE void next(const T& t) + { + serialize(*this, t); + } + + template<typename T> + ROS_FORCE_INLINE OStream& operator<<(const T& t) + { + serialize(*this, t); + return *this; + } +}; + + +/** + * \brief Length stream + * + * LStream is not what you would normally think of as a stream, but it is used in order to support + * allinone serializers. + */ +struct ROSCPP_SERIALIZATION_DECL LStream +{ + static const StreamType stream_type = stream_types::Length; + + LStream() + : count_(0) + {} + + /** + * \brief Add the length of an item to this length stream + */ + template<typename T> + ROS_FORCE_INLINE void next(const T& t) + { + count_ += serializationLength(t); + } + + /** + * \brief increment the length by len + */ + ROS_FORCE_INLINE uint32_t advance(uint32_t len) + { + uint32_t old = count_; + count_ += len; + return old; + } + + /** + * \brief Get the total length of this tream + */ + inline uint32_t getLength() { return count_; } + +private: + uint32_t count_; +}; + +/** + * \brief Serialize a message + */ +template<typename M> +inline SerializedMessage serializeMessage(const M& message) +{ + SerializedMessage m; + uint32_t len = serializationLength(message); + m.num_bytes = len + 4; + m.buf.reset(new uint8_t[m.num_bytes]); + + OStream s(m.buf.get(), (uint32_t)m.num_bytes); + serialize(s, (uint32_t)m.num_bytes - 4); + m.message_start = s.getData(); + serialize(s, message); + + return m; +} + +/** + * \brief Serialize a service response + */ +template<typename M> +inline SerializedMessage serializeServiceResponse(bool ok, const M& message) +{ + SerializedMessage m; + + if (ok) + { + uint32_t len = serializationLength(message); + m.num_bytes = len + 5; + m.buf.reset(new uint8_t[m.num_bytes]); + + OStream s(m.buf.get(), (uint32_t)m.num_bytes); + serialize(s, (uint8_t)ok); + serialize(s, (uint32_t)m.num_bytes - 5); + serialize(s, message); + } + else + { + uint32_t len = serializationLength(message); + m.num_bytes = len + 1; + m.buf.reset(new uint8_t[m.num_bytes]); + + OStream s(m.buf.get(), (uint32_t)m.num_bytes); + serialize(s, (uint8_t)ok); + serialize(s, message); + } + + return m; +} + +/** + * \brief Deserialize a message. If includes_length is true, skips the first 4 bytes + */ +template<typename M> +inline void deserializeMessage(const SerializedMessage& m, M& message) +{ + IStream s(m.message_start, m.num_bytes - (m.message_start - m.buf.get())); + deserialize(s, message); +} + + +// Additional serialization traits + +template<typename M> +struct PreDeserializeParams +{ + boost::shared_ptr<M> message; + boost::shared_ptr<std::map<std::string, std::string> > connection_header; +}; + +/** + * \brief called by the SubscriptionCallbackHelper after a message is + * instantiated but before that message is deserialized + */ +template<typename M> +struct PreDeserialize +{ + static void notify(const PreDeserializeParams<M>&) { } +}; + +} // namespace serialization + +} // namespace ros + +#endif // ROSCPP_SERIALIZATION_H \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/service_client.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_SERVICE_CLIENT_H_ +#define _ROS_SERVICE_CLIENT_H_ + +#include "rosserial_msgs/TopicInfo.h" + +#include "ros/publisher.h" +#include "ros/subscriber.h" + +namespace ros { + + template<typename MReq , typename MRes> + class ServiceClient : public Subscriber_ { + public: + ServiceClient(const char* topic_name) : + pub(topic_name, &req, rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_PUBLISHER) + { + this->topic_ = topic_name; + this->waiting = true; + } + + virtual void call(const MReq & request, MRes & response) + { + if(!pub.nh_->connected()) return; + ret = &response; + waiting = true; + pub.publish(&request); + while(waiting && pub.nh_->connected()) + if(pub.nh_->spinOnce() < 0) break; + } + + // these refer to the subscriber + virtual void callback(unsigned char *data){ + ret->deserialize(data); + waiting = false; + } + virtual const char * getMsgType(){ return this->resp.getType(); } + virtual const char * getMsgMD5(){ return this->resp.getMD5(); } + virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; } + + MReq req; + MRes resp; + MRes * ret; + bool waiting; + Publisher pub; + }; + +} + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/service_server.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,76 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_SERVICE_SERVER_H_ +#define _ROS_SERVICE_SERVER_H_ + +#include "rosserial_msgs/TopicInfo.h" + +#include "ros/publisher.h" +#include "ros/subscriber.h" + +namespace ros { + + template<typename MReq , typename MRes> + class ServiceServer : public Subscriber_ { + public: + typedef void(*CallbackT)(const MReq&, MRes&); + + ServiceServer(const char* topic_name, CallbackT cb) : + pub(topic_name, &resp, rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_PUBLISHER) + { + this->topic_ = topic_name; + this->cb_ = cb; + } + + // these refer to the subscriber + virtual void callback(unsigned char *data){ + req.deserialize(data); + cb_(req,resp); + pub.publish(&resp); + } + virtual const char * getMsgType(){ return this->req.getType(); } + virtual const char * getMsgMD5(){ return this->req.getMD5(); } + virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; } + + MReq req; + MRes resp; + Publisher pub; + private: + CallbackT cb_; + }; + +} + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/subscriber.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,121 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_SUBSCRIBER_H_ +#define ROS_SUBSCRIBER_H_ + +#include "rosserial_msgs/TopicInfo.h" + +namespace ros { + + /* Base class for objects subscribers. */ + class Subscriber_ + { + public: + virtual void callback(unsigned char *data)=0; + virtual int getEndpointType()=0; + + // id_ is set by NodeHandle when we advertise + int id_; + + virtual const char * getMsgType()=0; + virtual const char * getMsgMD5()=0; + const char * topic_; + }; + + /* Bound function subscriber. */ + template<typename MsgT, typename ObjT=void> + class Subscriber: public Subscriber_ + { + public: + typedef void(ObjT::*CallbackT)(const MsgT&); + MsgT msg; + + Subscriber(const char * topic_name, CallbackT cb, ObjT* obj, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) : + cb_(cb), + obj_(obj), + endpoint_(endpoint) + { + topic_ = topic_name; + }; + + virtual void callback(unsigned char* data) + { + msg.deserialize(data); + (obj_->*cb_)(msg); + } + + virtual const char * getMsgType() { return this->msg.getType(); } + virtual const char * getMsgMD5() { return this->msg.getMD5(); } + virtual int getEndpointType() { return endpoint_; } + + private: + CallbackT cb_; + ObjT* obj_; + int endpoint_; + }; + + /* Standalone function subscriber. */ + template<typename MsgT> + class Subscriber<MsgT, void>: public Subscriber_ + { + public: + typedef void(*CallbackT)(const MsgT&); + MsgT msg; + + Subscriber(const char * topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) : + cb_(cb), + endpoint_(endpoint) + { + topic_ = topic_name; + }; + + virtual void callback(unsigned char* data) + { + msg.deserialize(data); + this->cb_(msg); + } + + virtual const char * getMsgType() { return this->msg.getType(); } + virtual const char * getMsgMD5() { return this->msg.getMD5(); } + virtual int getEndpointType() { return endpoint_; } + + private: + CallbackT cb_; + int endpoint_; + }; + +} + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/time.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,73 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_TIME_H_ +#define ROS_TIME_H_ + +#include "ros/duration.h" +#include <math.h> +#include <stdint.h> + +namespace ros +{ + void normalizeSecNSec(uint32_t &sec, uint32_t &nsec); + + class Time + { + public: + uint32_t sec, nsec; + + Time() : sec(0), nsec(0) {} + Time(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec) + { + normalizeSecNSec(sec, nsec); + } + + double round(double number) { return number < 0.0 ? ceil(number - 0.5): floor(number + 0.5); } + double toSec() const { return (double)sec + 1e-9*(double)nsec; }; + void fromSec(double t) { sec = (uint32_t) floor(t); nsec = (uint32_t) round((t-sec) * 1e9); }; + + uint32_t toNsec() { return (uint32_t)sec*1000000000ull + (uint32_t)nsec; }; + Time& fromNSec(int32_t t); + + Time& operator +=(const Duration &rhs); + Time& operator -=(const Duration &rhs); + + static Time now(); + static void setNow( Time & new_now); + }; + +} + +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/types.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSCPP_TYPES_H +#define ROSCPP_TYPES_H + +// this is just for interoperability with visual studio, where the standard +// integer types are not defined. + +#if defined(_MSC_VER) && (_MSC_VER < 1600 ) // MS express/studio 2008 or earlier + typedef __int64 int64_t; + typedef unsigned __int64 uint64_t; + typedef __int32 int32_t; + typedef unsigned __int32 uint32_t; + typedef __int16 int16_t; + typedef unsigned __int16 uint16_t; + typedef __int8 int8_t; + typedef unsigned __int8 uint8_t; +#else + #include <stdint.h> +#endif + + +#endif // ROSCPP_TYPES_H \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/Log.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,67 @@ +#ifndef _ROS_rosserial_msgs_Log_h +#define _ROS_rosserial_msgs_Log_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + + class Log : public ros::Msg + { + public: + typedef uint8_t _level_type; + _level_type level; + typedef const char* _msg_type; + _msg_type msg; + enum { ROSDEBUG = 0 }; + enum { INFO = 1 }; + enum { WARN = 2 }; + enum { ERROR = 3 }; + enum { FATAL = 4 }; + + Log(): + level(0), + msg("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_msg = strlen(this->msg); + varToArr(outbuffer + offset, length_msg); + offset += 4; + memcpy(outbuffer + offset, this->msg, length_msg); + offset += length_msg; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->level = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->level); + uint32_t length_msg; + arrToVar(length_msg, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_msg; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_msg-1]=0; + this->msg = (char *)(inbuffer + offset-1); + offset += length_msg; + return offset; + } + + const char * getType(){ return "rosserial_msgs/Log"; }; + const char * getMD5(){ return "11abd731c25933261cd6183bd12d6295"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/RequestMessageInfo.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,121 @@ +#ifndef _ROS_SERVICE_RequestMessageInfo_h +#define _ROS_SERVICE_RequestMessageInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + +static const char REQUESTMESSAGEINFO[] = "rosserial_msgs/RequestMessageInfo"; + + class RequestMessageInfoRequest : public ros::Msg + { + public: + typedef const char* _type_type; + _type_type type; + + RequestMessageInfoRequest(): + type("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_type = strlen(this->type); + varToArr(outbuffer + offset, length_type); + offset += 4; + memcpy(outbuffer + offset, this->type, length_type); + offset += length_type; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_type; + arrToVar(length_type, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_type-1]=0; + this->type = (char *)(inbuffer + offset-1); + offset += length_type; + return offset; + } + + const char * getType(){ return REQUESTMESSAGEINFO; }; + const char * getMD5(){ return "dc67331de85cf97091b7d45e5c64ab75"; }; + + }; + + class RequestMessageInfoResponse : public ros::Msg + { + public: + typedef const char* _md5_type; + _md5_type md5; + typedef const char* _definition_type; + _definition_type definition; + + RequestMessageInfoResponse(): + md5(""), + definition("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_md5 = strlen(this->md5); + varToArr(outbuffer + offset, length_md5); + offset += 4; + memcpy(outbuffer + offset, this->md5, length_md5); + offset += length_md5; + uint32_t length_definition = strlen(this->definition); + varToArr(outbuffer + offset, length_definition); + offset += 4; + memcpy(outbuffer + offset, this->definition, length_definition); + offset += length_definition; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_md5; + arrToVar(length_md5, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_md5-1]=0; + this->md5 = (char *)(inbuffer + offset-1); + offset += length_md5; + uint32_t length_definition; + arrToVar(length_definition, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_definition; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_definition-1]=0; + this->definition = (char *)(inbuffer + offset-1); + offset += length_definition; + return offset; + } + + const char * getType(){ return REQUESTMESSAGEINFO; }; + const char * getMD5(){ return "fe452186a069bed40f09b8628fe5eac8"; }; + + }; + + class RequestMessageInfo { + public: + typedef RequestMessageInfoRequest Request; + typedef RequestMessageInfoResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/RequestParam.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,212 @@ +#ifndef _ROS_SERVICE_RequestParam_h +#define _ROS_SERVICE_RequestParam_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + +static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam"; + + class RequestParamRequest : public ros::Msg + { + public: + typedef const char* _name_type; + _name_type name; + + RequestParamRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + varToArr(outbuffer + offset, length_name); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + arrToVar(length_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return REQUESTPARAM; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class RequestParamResponse : public ros::Msg + { + public: + uint32_t ints_length; + typedef int32_t _ints_type; + _ints_type st_ints; + _ints_type * ints; + uint32_t floats_length; + typedef float _floats_type; + _floats_type st_floats; + _floats_type * floats; + uint32_t strings_length; + typedef char* _strings_type; + _strings_type st_strings; + _strings_type * strings; + + RequestParamResponse(): + ints_length(0), ints(NULL), + floats_length(0), floats(NULL), + strings_length(0), strings(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->ints_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->ints_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->ints_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->ints_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->ints_length); + for( uint32_t i = 0; i < ints_length; i++){ + union { + int32_t real; + uint32_t base; + } u_intsi; + u_intsi.real = this->ints[i]; + *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->ints[i]); + } + *(outbuffer + offset + 0) = (this->floats_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->floats_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->floats_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->floats_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->floats_length); + for( uint32_t i = 0; i < floats_length; i++){ + union { + float real; + uint32_t base; + } u_floatsi; + u_floatsi.real = this->floats[i]; + *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->floats[i]); + } + *(outbuffer + offset + 0) = (this->strings_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->strings_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->strings_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->strings_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->strings_length); + for( uint32_t i = 0; i < strings_length; i++){ + uint32_t length_stringsi = strlen(this->strings[i]); + varToArr(outbuffer + offset, length_stringsi); + offset += 4; + memcpy(outbuffer + offset, this->strings[i], length_stringsi); + offset += length_stringsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t ints_lengthT = ((uint32_t) (*(inbuffer + offset))); + ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->ints_length); + if(ints_lengthT > ints_length) + this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t)); + ints_length = ints_lengthT; + for( uint32_t i = 0; i < ints_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_ints; + u_st_ints.base = 0; + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_ints = u_st_ints.real; + offset += sizeof(this->st_ints); + memcpy( &(this->ints[i]), &(this->st_ints), sizeof(int32_t)); + } + uint32_t floats_lengthT = ((uint32_t) (*(inbuffer + offset))); + floats_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + floats_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + floats_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->floats_length); + if(floats_lengthT > floats_length) + this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float)); + floats_length = floats_lengthT; + for( uint32_t i = 0; i < floats_length; i++){ + union { + float real; + uint32_t base; + } u_st_floats; + u_st_floats.base = 0; + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_floats = u_st_floats.real; + offset += sizeof(this->st_floats); + memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float)); + } + uint32_t strings_lengthT = ((uint32_t) (*(inbuffer + offset))); + strings_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + strings_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + strings_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->strings_length); + if(strings_lengthT > strings_length) + this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*)); + strings_length = strings_lengthT; + for( uint32_t i = 0; i < strings_length; i++){ + uint32_t length_st_strings; + arrToVar(length_st_strings, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_strings; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_strings-1]=0; + this->st_strings = (char *)(inbuffer + offset-1); + offset += length_st_strings; + memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return REQUESTPARAM; }; + const char * getMD5(){ return "9f0e98bda65981986ddf53afa7a40e49"; }; + + }; + + class RequestParam { + public: + typedef RequestParamRequest Request; + typedef RequestParamResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/RequestServiceInfo.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,138 @@ +#ifndef _ROS_SERVICE_RequestServiceInfo_h +#define _ROS_SERVICE_RequestServiceInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + +static const char REQUESTSERVICEINFO[] = "rosserial_msgs/RequestServiceInfo"; + + class RequestServiceInfoRequest : public ros::Msg + { + public: + typedef const char* _service_type; + _service_type service; + + RequestServiceInfoRequest(): + service("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_service = strlen(this->service); + varToArr(outbuffer + offset, length_service); + offset += 4; + memcpy(outbuffer + offset, this->service, length_service); + offset += length_service; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_service; + arrToVar(length_service, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_service; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_service-1]=0; + this->service = (char *)(inbuffer + offset-1); + offset += length_service; + return offset; + } + + const char * getType(){ return REQUESTSERVICEINFO; }; + const char * getMD5(){ return "1cbcfa13b08f6d36710b9af8741e6112"; }; + + }; + + class RequestServiceInfoResponse : public ros::Msg + { + public: + typedef const char* _service_md5_type; + _service_md5_type service_md5; + typedef const char* _request_md5_type; + _request_md5_type request_md5; + typedef const char* _response_md5_type; + _response_md5_type response_md5; + + RequestServiceInfoResponse(): + service_md5(""), + request_md5(""), + response_md5("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_service_md5 = strlen(this->service_md5); + varToArr(outbuffer + offset, length_service_md5); + offset += 4; + memcpy(outbuffer + offset, this->service_md5, length_service_md5); + offset += length_service_md5; + uint32_t length_request_md5 = strlen(this->request_md5); + varToArr(outbuffer + offset, length_request_md5); + offset += 4; + memcpy(outbuffer + offset, this->request_md5, length_request_md5); + offset += length_request_md5; + uint32_t length_response_md5 = strlen(this->response_md5); + varToArr(outbuffer + offset, length_response_md5); + offset += 4; + memcpy(outbuffer + offset, this->response_md5, length_response_md5); + offset += length_response_md5; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_service_md5; + arrToVar(length_service_md5, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_service_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_service_md5-1]=0; + this->service_md5 = (char *)(inbuffer + offset-1); + offset += length_service_md5; + uint32_t length_request_md5; + arrToVar(length_request_md5, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_request_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_request_md5-1]=0; + this->request_md5 = (char *)(inbuffer + offset-1); + offset += length_request_md5; + uint32_t length_response_md5; + arrToVar(length_response_md5, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_response_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_response_md5-1]=0; + this->response_md5 = (char *)(inbuffer + offset-1); + offset += length_response_md5; + return offset; + } + + const char * getType(){ return REQUESTSERVICEINFO; }; + const char * getMD5(){ return "c3d6dd25b909596479fbbc6559fa6874"; }; + + }; + + class RequestServiceInfo { + public: + typedef RequestServiceInfoRequest Request; + typedef RequestServiceInfoResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/TopicInfo.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,130 @@ +#ifndef _ROS_rosserial_msgs_TopicInfo_h +#define _ROS_rosserial_msgs_TopicInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + + class TopicInfo : public ros::Msg + { + public: + typedef uint16_t _topic_id_type; + _topic_id_type topic_id; + typedef const char* _topic_name_type; + _topic_name_type topic_name; + typedef const char* _message_type_type; + _message_type_type message_type; + typedef const char* _md5sum_type; + _md5sum_type md5sum; + typedef int32_t _buffer_size_type; + _buffer_size_type buffer_size; + enum { ID_PUBLISHER = 0 }; + enum { ID_SUBSCRIBER = 1 }; + enum { ID_SERVICE_SERVER = 2 }; + enum { ID_SERVICE_CLIENT = 4 }; + enum { ID_PARAMETER_REQUEST = 6 }; + enum { ID_LOG = 7 }; + enum { ID_TIME = 10 }; + enum { ID_TX_STOP = 11 }; + + TopicInfo(): + topic_id(0), + topic_name(""), + message_type(""), + md5sum(""), + buffer_size(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF; + offset += sizeof(this->topic_id); + uint32_t length_topic_name = strlen(this->topic_name); + varToArr(outbuffer + offset, length_topic_name); + offset += 4; + memcpy(outbuffer + offset, this->topic_name, length_topic_name); + offset += length_topic_name; + uint32_t length_message_type = strlen(this->message_type); + varToArr(outbuffer + offset, length_message_type); + offset += 4; + memcpy(outbuffer + offset, this->message_type, length_message_type); + offset += length_message_type; + uint32_t length_md5sum = strlen(this->md5sum); + varToArr(outbuffer + offset, length_md5sum); + offset += 4; + memcpy(outbuffer + offset, this->md5sum, length_md5sum); + offset += length_md5sum; + union { + int32_t real; + uint32_t base; + } u_buffer_size; + u_buffer_size.real = this->buffer_size; + *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->buffer_size); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->topic_id = ((uint16_t) (*(inbuffer + offset))); + this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->topic_id); + uint32_t length_topic_name; + arrToVar(length_topic_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic_name-1]=0; + this->topic_name = (char *)(inbuffer + offset-1); + offset += length_topic_name; + uint32_t length_message_type; + arrToVar(length_message_type, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_message_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_message_type-1]=0; + this->message_type = (char *)(inbuffer + offset-1); + offset += length_message_type; + uint32_t length_md5sum; + arrToVar(length_md5sum, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_md5sum; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_md5sum-1]=0; + this->md5sum = (char *)(inbuffer + offset-1); + offset += length_md5sum; + union { + int32_t real; + uint32_t base; + } u_buffer_size; + u_buffer_size.base = 0; + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->buffer_size = u_buffer_size.real; + offset += sizeof(this->buffer_size); + return offset; + } + + const char * getType(){ return "rosserial_msgs/TopicInfo"; }; + const char * getMD5(){ return "0ad51f88fc44892f8c10684077646005"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/BatteryState.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,326 @@ +#ifndef _ROS_sensor_msgs_BatteryState_h +#define _ROS_sensor_msgs_BatteryState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class BatteryState : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef float _voltage_type; + _voltage_type voltage; + typedef float _current_type; + _current_type current; + typedef float _charge_type; + _charge_type charge; + typedef float _capacity_type; + _capacity_type capacity; + typedef float _design_capacity_type; + _design_capacity_type design_capacity; + typedef float _percentage_type; + _percentage_type percentage; + typedef uint8_t _power_supply_status_type; + _power_supply_status_type power_supply_status; + typedef uint8_t _power_supply_health_type; + _power_supply_health_type power_supply_health; + typedef uint8_t _power_supply_technology_type; + _power_supply_technology_type power_supply_technology; + typedef bool _present_type; + _present_type present; + uint32_t cell_voltage_length; + typedef float _cell_voltage_type; + _cell_voltage_type st_cell_voltage; + _cell_voltage_type * cell_voltage; + typedef const char* _location_type; + _location_type location; + typedef const char* _serial_number_type; + _serial_number_type serial_number; + enum { POWER_SUPPLY_STATUS_UNKNOWN = 0 }; + enum { POWER_SUPPLY_STATUS_CHARGING = 1 }; + enum { POWER_SUPPLY_STATUS_DISCHARGING = 2 }; + enum { POWER_SUPPLY_STATUS_NOT_CHARGING = 3 }; + enum { POWER_SUPPLY_STATUS_FULL = 4 }; + enum { POWER_SUPPLY_HEALTH_UNKNOWN = 0 }; + enum { POWER_SUPPLY_HEALTH_GOOD = 1 }; + enum { POWER_SUPPLY_HEALTH_OVERHEAT = 2 }; + enum { POWER_SUPPLY_HEALTH_DEAD = 3 }; + enum { POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 }; + enum { POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 }; + enum { POWER_SUPPLY_HEALTH_COLD = 6 }; + enum { POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 }; + enum { POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 }; + enum { POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 }; + enum { POWER_SUPPLY_TECHNOLOGY_NIMH = 1 }; + enum { POWER_SUPPLY_TECHNOLOGY_LION = 2 }; + enum { POWER_SUPPLY_TECHNOLOGY_LIPO = 3 }; + enum { POWER_SUPPLY_TECHNOLOGY_LIFE = 4 }; + enum { POWER_SUPPLY_TECHNOLOGY_NICD = 5 }; + enum { POWER_SUPPLY_TECHNOLOGY_LIMN = 6 }; + + BatteryState(): + header(), + voltage(0), + current(0), + charge(0), + capacity(0), + design_capacity(0), + percentage(0), + power_supply_status(0), + power_supply_health(0), + power_supply_technology(0), + present(0), + cell_voltage_length(0), cell_voltage(NULL), + location(""), + serial_number("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_voltage; + u_voltage.real = this->voltage; + *(outbuffer + offset + 0) = (u_voltage.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_voltage.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_voltage.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_voltage.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->voltage); + union { + float real; + uint32_t base; + } u_current; + u_current.real = this->current; + *(outbuffer + offset + 0) = (u_current.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_current.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_current.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_current.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->current); + union { + float real; + uint32_t base; + } u_charge; + u_charge.real = this->charge; + *(outbuffer + offset + 0) = (u_charge.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_charge.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_charge.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_charge.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->charge); + union { + float real; + uint32_t base; + } u_capacity; + u_capacity.real = this->capacity; + *(outbuffer + offset + 0) = (u_capacity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_capacity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_capacity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_capacity.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->capacity); + union { + float real; + uint32_t base; + } u_design_capacity; + u_design_capacity.real = this->design_capacity; + *(outbuffer + offset + 0) = (u_design_capacity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_design_capacity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_design_capacity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_design_capacity.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->design_capacity); + union { + float real; + uint32_t base; + } u_percentage; + u_percentage.real = this->percentage; + *(outbuffer + offset + 0) = (u_percentage.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_percentage.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_percentage.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_percentage.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->percentage); + *(outbuffer + offset + 0) = (this->power_supply_status >> (8 * 0)) & 0xFF; + offset += sizeof(this->power_supply_status); + *(outbuffer + offset + 0) = (this->power_supply_health >> (8 * 0)) & 0xFF; + offset += sizeof(this->power_supply_health); + *(outbuffer + offset + 0) = (this->power_supply_technology >> (8 * 0)) & 0xFF; + offset += sizeof(this->power_supply_technology); + union { + bool real; + uint8_t base; + } u_present; + u_present.real = this->present; + *(outbuffer + offset + 0) = (u_present.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->present); + *(outbuffer + offset + 0) = (this->cell_voltage_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->cell_voltage_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->cell_voltage_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->cell_voltage_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->cell_voltage_length); + for( uint32_t i = 0; i < cell_voltage_length; i++){ + union { + float real; + uint32_t base; + } u_cell_voltagei; + u_cell_voltagei.real = this->cell_voltage[i]; + *(outbuffer + offset + 0) = (u_cell_voltagei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_cell_voltagei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_cell_voltagei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_cell_voltagei.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->cell_voltage[i]); + } + uint32_t length_location = strlen(this->location); + varToArr(outbuffer + offset, length_location); + offset += 4; + memcpy(outbuffer + offset, this->location, length_location); + offset += length_location; + uint32_t length_serial_number = strlen(this->serial_number); + varToArr(outbuffer + offset, length_serial_number); + offset += 4; + memcpy(outbuffer + offset, this->serial_number, length_serial_number); + offset += length_serial_number; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_voltage; + u_voltage.base = 0; + u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->voltage = u_voltage.real; + offset += sizeof(this->voltage); + union { + float real; + uint32_t base; + } u_current; + u_current.base = 0; + u_current.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_current.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_current.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_current.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->current = u_current.real; + offset += sizeof(this->current); + union { + float real; + uint32_t base; + } u_charge; + u_charge.base = 0; + u_charge.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_charge.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_charge.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_charge.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->charge = u_charge.real; + offset += sizeof(this->charge); + union { + float real; + uint32_t base; + } u_capacity; + u_capacity.base = 0; + u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->capacity = u_capacity.real; + offset += sizeof(this->capacity); + union { + float real; + uint32_t base; + } u_design_capacity; + u_design_capacity.base = 0; + u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->design_capacity = u_design_capacity.real; + offset += sizeof(this->design_capacity); + union { + float real; + uint32_t base; + } u_percentage; + u_percentage.base = 0; + u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->percentage = u_percentage.real; + offset += sizeof(this->percentage); + this->power_supply_status = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->power_supply_status); + this->power_supply_health = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->power_supply_health); + this->power_supply_technology = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->power_supply_technology); + union { + bool real; + uint8_t base; + } u_present; + u_present.base = 0; + u_present.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->present = u_present.real; + offset += sizeof(this->present); + uint32_t cell_voltage_lengthT = ((uint32_t) (*(inbuffer + offset))); + cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->cell_voltage_length); + if(cell_voltage_lengthT > cell_voltage_length) + this->cell_voltage = (float*)realloc(this->cell_voltage, cell_voltage_lengthT * sizeof(float)); + cell_voltage_length = cell_voltage_lengthT; + for( uint32_t i = 0; i < cell_voltage_length; i++){ + union { + float real; + uint32_t base; + } u_st_cell_voltage; + u_st_cell_voltage.base = 0; + u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_cell_voltage = u_st_cell_voltage.real; + offset += sizeof(this->st_cell_voltage); + memcpy( &(this->cell_voltage[i]), &(this->st_cell_voltage), sizeof(float)); + } + uint32_t length_location; + arrToVar(length_location, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_location; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_location-1]=0; + this->location = (char *)(inbuffer + offset-1); + offset += length_location; + uint32_t length_serial_number; + arrToVar(length_serial_number, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_serial_number; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_serial_number-1]=0; + this->serial_number = (char *)(inbuffer + offset-1); + offset += length_serial_number; + return offset; + } + + const char * getType(){ return "sensor_msgs/BatteryState"; }; + const char * getMD5(){ return "476f837fa6771f6e16e3bf4ef96f8770"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/CameraInfo.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,276 @@ +#ifndef _ROS_sensor_msgs_CameraInfo_h +#define _ROS_sensor_msgs_CameraInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/RegionOfInterest.h" + +namespace sensor_msgs +{ + + class CameraInfo : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef uint32_t _height_type; + _height_type height; + typedef uint32_t _width_type; + _width_type width; + typedef const char* _distortion_model_type; + _distortion_model_type distortion_model; + uint32_t D_length; + typedef double _D_type; + _D_type st_D; + _D_type * D; + double K[9]; + double R[9]; + double P[12]; + typedef uint32_t _binning_x_type; + _binning_x_type binning_x; + typedef uint32_t _binning_y_type; + _binning_y_type binning_y; + typedef sensor_msgs::RegionOfInterest _roi_type; + _roi_type roi; + + CameraInfo(): + header(), + height(0), + width(0), + distortion_model(""), + D_length(0), D(NULL), + K(), + R(), + P(), + binning_x(0), + binning_y(0), + roi() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + uint32_t length_distortion_model = strlen(this->distortion_model); + varToArr(outbuffer + offset, length_distortion_model); + offset += 4; + memcpy(outbuffer + offset, this->distortion_model, length_distortion_model); + offset += length_distortion_model; + *(outbuffer + offset + 0) = (this->D_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->D_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->D_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->D_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->D_length); + for( uint32_t i = 0; i < D_length; i++){ + union { + double real; + uint64_t base; + } u_Di; + u_Di.real = this->D[i]; + *(outbuffer + offset + 0) = (u_Di.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_Di.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_Di.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_Di.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_Di.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_Di.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_Di.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_Di.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->D[i]); + } + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_Ki; + u_Ki.real = this->K[i]; + *(outbuffer + offset + 0) = (u_Ki.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_Ki.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_Ki.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_Ki.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_Ki.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_Ki.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_Ki.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_Ki.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->K[i]); + } + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_Ri; + u_Ri.real = this->R[i]; + *(outbuffer + offset + 0) = (u_Ri.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_Ri.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_Ri.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_Ri.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_Ri.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_Ri.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_Ri.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_Ri.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->R[i]); + } + for( uint32_t i = 0; i < 12; i++){ + union { + double real; + uint64_t base; + } u_Pi; + u_Pi.real = this->P[i]; + *(outbuffer + offset + 0) = (u_Pi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_Pi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_Pi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_Pi.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_Pi.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_Pi.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_Pi.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_Pi.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->P[i]); + } + *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF; + offset += sizeof(this->binning_x); + *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF; + offset += sizeof(this->binning_y); + offset += this->roi.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint32_t length_distortion_model; + arrToVar(length_distortion_model, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_distortion_model; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_distortion_model-1]=0; + this->distortion_model = (char *)(inbuffer + offset-1); + offset += length_distortion_model; + uint32_t D_lengthT = ((uint32_t) (*(inbuffer + offset))); + D_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + D_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + D_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->D_length); + if(D_lengthT > D_length) + this->D = (double*)realloc(this->D, D_lengthT * sizeof(double)); + D_length = D_lengthT; + for( uint32_t i = 0; i < D_length; i++){ + union { + double real; + uint64_t base; + } u_st_D; + u_st_D.base = 0; + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_D = u_st_D.real; + offset += sizeof(this->st_D); + memcpy( &(this->D[i]), &(this->st_D), sizeof(double)); + } + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_Ki; + u_Ki.base = 0; + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->K[i] = u_Ki.real; + offset += sizeof(this->K[i]); + } + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_Ri; + u_Ri.base = 0; + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->R[i] = u_Ri.real; + offset += sizeof(this->R[i]); + } + for( uint32_t i = 0; i < 12; i++){ + union { + double real; + uint64_t base; + } u_Pi; + u_Pi.base = 0; + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->P[i] = u_Pi.real; + offset += sizeof(this->P[i]); + } + this->binning_x = ((uint32_t) (*(inbuffer + offset))); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->binning_x); + this->binning_y = ((uint32_t) (*(inbuffer + offset))); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->binning_y); + offset += this->roi.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "sensor_msgs/CameraInfo"; }; + const char * getMD5(){ return "c9a58c1b0b154e0e6da7578cb991d214"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/ChannelFloat32.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,99 @@ +#ifndef _ROS_sensor_msgs_ChannelFloat32_h +#define _ROS_sensor_msgs_ChannelFloat32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class ChannelFloat32 : public ros::Msg + { + public: + typedef const char* _name_type; + _name_type name; + uint32_t values_length; + typedef float _values_type; + _values_type st_values; + _values_type * values; + + ChannelFloat32(): + name(""), + values_length(0), values(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + varToArr(outbuffer + offset, length_name); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset + 0) = (this->values_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->values_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->values_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->values_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->values_length); + for( uint32_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_valuesi; + u_valuesi.real = this->values[i]; + *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->values[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + arrToVar(length_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t values_lengthT = ((uint32_t) (*(inbuffer + offset))); + values_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + values_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + values_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->values_length); + if(values_lengthT > values_length) + this->values = (float*)realloc(this->values, values_lengthT * sizeof(float)); + values_length = values_lengthT; + for( uint32_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_st_values; + u_st_values.base = 0; + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_values = u_st_values.real; + offset += sizeof(this->st_values); + memcpy( &(this->values[i]), &(this->st_values), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/ChannelFloat32"; }; + const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/CompressedImage.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,88 @@ +#ifndef _ROS_sensor_msgs_CompressedImage_h +#define _ROS_sensor_msgs_CompressedImage_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class CompressedImage : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef const char* _format_type; + _format_type format; + uint32_t data_length; + typedef uint8_t _data_type; + _data_type st_data; + _data_type * data; + + CompressedImage(): + header(), + format(""), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_format = strlen(this->format); + varToArr(outbuffer + offset, length_format); + offset += 4; + memcpy(outbuffer + offset, this->format, length_format); + offset += length_format; + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_format; + arrToVar(length_format, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_format; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_format-1]=0; + this->format = (char *)(inbuffer + offset-1); + offset += length_format; + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/CompressedImage"; }; + const char * getMD5(){ return "8f7a12909da2c9d3332d540a0977563f"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/FluidPressure.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,108 @@ +#ifndef _ROS_sensor_msgs_FluidPressure_h +#define _ROS_sensor_msgs_FluidPressure_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class FluidPressure : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef double _fluid_pressure_type; + _fluid_pressure_type fluid_pressure; + typedef double _variance_type; + _variance_type variance; + + FluidPressure(): + header(), + fluid_pressure(0), + variance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + double real; + uint64_t base; + } u_fluid_pressure; + u_fluid_pressure.real = this->fluid_pressure; + *(outbuffer + offset + 0) = (u_fluid_pressure.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_fluid_pressure.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_fluid_pressure.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_fluid_pressure.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_fluid_pressure.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_fluid_pressure.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_fluid_pressure.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_fluid_pressure.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->fluid_pressure); + union { + double real; + uint64_t base; + } u_variance; + u_variance.real = this->variance; + *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->variance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + double real; + uint64_t base; + } u_fluid_pressure; + u_fluid_pressure.base = 0; + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->fluid_pressure = u_fluid_pressure.real; + offset += sizeof(this->fluid_pressure); + union { + double real; + uint64_t base; + } u_variance; + u_variance.base = 0; + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->variance = u_variance.real; + offset += sizeof(this->variance); + return offset; + } + + const char * getType(){ return "sensor_msgs/FluidPressure"; }; + const char * getMD5(){ return "804dc5cea1c5306d6a2eb80b9833befe"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Illuminance.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,108 @@ +#ifndef _ROS_sensor_msgs_Illuminance_h +#define _ROS_sensor_msgs_Illuminance_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Illuminance : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef double _illuminance_type; + _illuminance_type illuminance; + typedef double _variance_type; + _variance_type variance; + + Illuminance(): + header(), + illuminance(0), + variance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + double real; + uint64_t base; + } u_illuminance; + u_illuminance.real = this->illuminance; + *(outbuffer + offset + 0) = (u_illuminance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_illuminance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_illuminance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_illuminance.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_illuminance.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_illuminance.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_illuminance.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_illuminance.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->illuminance); + union { + double real; + uint64_t base; + } u_variance; + u_variance.real = this->variance; + *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->variance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + double real; + uint64_t base; + } u_illuminance; + u_illuminance.base = 0; + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->illuminance = u_illuminance.real; + offset += sizeof(this->illuminance); + union { + double real; + uint64_t base; + } u_variance; + u_variance.base = 0; + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->variance = u_variance.real; + offset += sizeof(this->variance); + return offset; + } + + const char * getType(){ return "sensor_msgs/Illuminance"; }; + const char * getMD5(){ return "8cf5febb0952fca9d650c3d11a81a188"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Image.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,135 @@ +#ifndef _ROS_sensor_msgs_Image_h +#define _ROS_sensor_msgs_Image_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include <vector> + +namespace sensor_msgs +{ + + class Image : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef uint32_t _height_type; + _height_type height; + typedef uint32_t _width_type; + _width_type width; + typedef const char* _encoding_type; + _encoding_type encoding; + typedef uint8_t _is_bigendian_type; + _is_bigendian_type is_bigendian; + typedef uint32_t _step_type; + _step_type step; + uint32_t data_length; + typedef uint8_t _data_type; + _data_type st_data; + _data_type * data; + + Image(): + header(), + height(0), + width(0), + encoding(""), + is_bigendian(0), + step(0), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + uint32_t length_encoding = strlen(this->encoding); + varToArr(outbuffer + offset, length_encoding); + offset += 4; + memcpy(outbuffer + offset, this->encoding, length_encoding); + offset += length_encoding; + *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_bigendian); + *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF; + offset += sizeof(this->step); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint32_t length_encoding; + arrToVar(length_encoding, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_encoding; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_encoding-1]=0; + this->encoding = (char *)(inbuffer + offset-1); + offset += length_encoding; + this->is_bigendian = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->is_bigendian); + this->step = ((uint32_t) (*(inbuffer + offset))); + this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->step); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/Image"; }; + const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Imu.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,166 @@ +#ifndef _ROS_sensor_msgs_Imu_h +#define _ROS_sensor_msgs_Imu_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Quaternion.h" +#include "geometry_msgs/Vector3.h" + +namespace sensor_msgs +{ + + class Imu : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef geometry_msgs::Quaternion _orientation_type; + _orientation_type orientation; + double orientation_covariance[9]; + typedef geometry_msgs::Vector3 _angular_velocity_type; + _angular_velocity_type angular_velocity; + double angular_velocity_covariance[9]; + typedef geometry_msgs::Vector3 _linear_acceleration_type; + _linear_acceleration_type linear_acceleration; + double linear_acceleration_covariance[9]; + + Imu(): + header(), + orientation(), + orientation_covariance(), + angular_velocity(), + angular_velocity_covariance(), + linear_acceleration(), + linear_acceleration_covariance() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->orientation.serialize(outbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_orientation_covariancei; + u_orientation_covariancei.real = this->orientation_covariance[i]; + *(outbuffer + offset + 0) = (u_orientation_covariancei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_orientation_covariancei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_orientation_covariancei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_orientation_covariancei.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_orientation_covariancei.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_orientation_covariancei.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_orientation_covariancei.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_orientation_covariancei.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->orientation_covariance[i]); + } + offset += this->angular_velocity.serialize(outbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_angular_velocity_covariancei; + u_angular_velocity_covariancei.real = this->angular_velocity_covariance[i]; + *(outbuffer + offset + 0) = (u_angular_velocity_covariancei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angular_velocity_covariancei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angular_velocity_covariancei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angular_velocity_covariancei.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_angular_velocity_covariancei.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_angular_velocity_covariancei.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_angular_velocity_covariancei.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_angular_velocity_covariancei.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->angular_velocity_covariance[i]); + } + offset += this->linear_acceleration.serialize(outbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_linear_acceleration_covariancei; + u_linear_acceleration_covariancei.real = this->linear_acceleration_covariance[i]; + *(outbuffer + offset + 0) = (u_linear_acceleration_covariancei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_linear_acceleration_covariancei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_linear_acceleration_covariancei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_linear_acceleration_covariancei.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_linear_acceleration_covariancei.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_linear_acceleration_covariancei.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_linear_acceleration_covariancei.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_linear_acceleration_covariancei.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->linear_acceleration_covariance[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->orientation.deserialize(inbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_orientation_covariancei; + u_orientation_covariancei.base = 0; + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->orientation_covariance[i] = u_orientation_covariancei.real; + offset += sizeof(this->orientation_covariance[i]); + } + offset += this->angular_velocity.deserialize(inbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_angular_velocity_covariancei; + u_angular_velocity_covariancei.base = 0; + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->angular_velocity_covariance[i] = u_angular_velocity_covariancei.real; + offset += sizeof(this->angular_velocity_covariance[i]); + } + offset += this->linear_acceleration.deserialize(inbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_linear_acceleration_covariancei; + u_linear_acceleration_covariancei.base = 0; + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->linear_acceleration_covariance[i] = u_linear_acceleration_covariancei.real; + offset += sizeof(this->linear_acceleration_covariance[i]); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/Imu"; }; + const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/JointState.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,237 @@ +#ifndef _ROS_sensor_msgs_JointState_h +#define _ROS_sensor_msgs_JointState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class JointState : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + uint32_t name_length; + typedef char* _name_type; + _name_type st_name; + _name_type * name; + uint32_t position_length; + typedef double _position_type; + _position_type st_position; + _position_type * position; + uint32_t velocity_length; + typedef double _velocity_type; + _velocity_type st_velocity; + _velocity_type * velocity; + uint32_t effort_length; + typedef double _effort_type; + _effort_type st_effort; + _effort_type * effort; + + JointState(): + header(), + name_length(0), name(NULL), + position_length(0), position(NULL), + velocity_length(0), velocity(NULL), + effort_length(0), effort(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->name_length); + for( uint32_t i = 0; i < name_length; i++){ + uint32_t length_namei = strlen(this->name[i]); + varToArr(outbuffer + offset, length_namei); + offset += 4; + memcpy(outbuffer + offset, this->name[i], length_namei); + offset += length_namei; + } + *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->position_length); + for( uint32_t i = 0; i < position_length; i++){ + union { + double real; + uint64_t base; + } u_positioni; + u_positioni.real = this->position[i]; + *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->position[i]); + } + *(outbuffer + offset + 0) = (this->velocity_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->velocity_length); + for( uint32_t i = 0; i < velocity_length; i++){ + union { + double real; + uint64_t base; + } u_velocityi; + u_velocityi.real = this->velocity[i]; + *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->velocity[i]); + } + *(outbuffer + offset + 0) = (this->effort_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->effort_length); + for( uint32_t i = 0; i < effort_length; i++){ + union { + double real; + uint64_t base; + } u_efforti; + u_efforti.real = this->effort[i]; + *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->effort[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); + name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->name_length); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + name_length = name_lengthT; + for( uint32_t i = 0; i < name_length; i++){ + uint32_t length_st_name; + arrToVar(length_st_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_name-1]=0; + this->st_name = (char *)(inbuffer + offset-1); + offset += length_st_name; + memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); + } + uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset))); + position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->position_length); + if(position_lengthT > position_length) + this->position = (double*)realloc(this->position, position_lengthT * sizeof(double)); + position_length = position_lengthT; + for( uint32_t i = 0; i < position_length; i++){ + union { + double real; + uint64_t base; + } u_st_position; + u_st_position.base = 0; + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_position = u_st_position.real; + offset += sizeof(this->st_position); + memcpy( &(this->position[i]), &(this->st_position), sizeof(double)); + } + uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset))); + velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->velocity_length); + if(velocity_lengthT > velocity_length) + this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double)); + velocity_length = velocity_lengthT; + for( uint32_t i = 0; i < velocity_length; i++){ + union { + double real; + uint64_t base; + } u_st_velocity; + u_st_velocity.base = 0; + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_velocity = u_st_velocity.real; + offset += sizeof(this->st_velocity); + memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double)); + } + uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset))); + effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->effort_length); + if(effort_lengthT > effort_length) + this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double)); + effort_length = effort_lengthT; + for( uint32_t i = 0; i < effort_length; i++){ + union { + double real; + uint64_t base; + } u_st_effort; + u_st_effort.base = 0; + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_effort = u_st_effort.real; + offset += sizeof(this->st_effort); + memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/JointState"; }; + const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Joy.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,132 @@ +#ifndef _ROS_sensor_msgs_Joy_h +#define _ROS_sensor_msgs_Joy_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Joy : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + uint32_t axes_length; + typedef float _axes_type; + _axes_type st_axes; + _axes_type * axes; + uint32_t buttons_length; + typedef int32_t _buttons_type; + _buttons_type st_buttons; + _buttons_type * buttons; + + Joy(): + header(), + axes_length(0), axes(NULL), + buttons_length(0), buttons(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->axes_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->axes_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->axes_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->axes_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->axes_length); + for( uint32_t i = 0; i < axes_length; i++){ + union { + float real; + uint32_t base; + } u_axesi; + u_axesi.real = this->axes[i]; + *(outbuffer + offset + 0) = (u_axesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_axesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_axesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_axesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->axes[i]); + } + *(outbuffer + offset + 0) = (this->buttons_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->buttons_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->buttons_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->buttons_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->buttons_length); + for( uint32_t i = 0; i < buttons_length; i++){ + union { + int32_t real; + uint32_t base; + } u_buttonsi; + u_buttonsi.real = this->buttons[i]; + *(outbuffer + offset + 0) = (u_buttonsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_buttonsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_buttonsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_buttonsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->buttons[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t axes_lengthT = ((uint32_t) (*(inbuffer + offset))); + axes_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + axes_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + axes_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->axes_length); + if(axes_lengthT > axes_length) + this->axes = (float*)realloc(this->axes, axes_lengthT * sizeof(float)); + axes_length = axes_lengthT; + for( uint32_t i = 0; i < axes_length; i++){ + union { + float real; + uint32_t base; + } u_st_axes; + u_st_axes.base = 0; + u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_axes = u_st_axes.real; + offset += sizeof(this->st_axes); + memcpy( &(this->axes[i]), &(this->st_axes), sizeof(float)); + } + uint32_t buttons_lengthT = ((uint32_t) (*(inbuffer + offset))); + buttons_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + buttons_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + buttons_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->buttons_length); + if(buttons_lengthT > buttons_length) + this->buttons = (int32_t*)realloc(this->buttons, buttons_lengthT * sizeof(int32_t)); + buttons_length = buttons_lengthT; + for( uint32_t i = 0; i < buttons_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_buttons; + u_st_buttons.base = 0; + u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_buttons = u_st_buttons.real; + offset += sizeof(this->st_buttons); + memcpy( &(this->buttons[i]), &(this->st_buttons), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/Joy"; }; + const char * getMD5(){ return "5a9ea5f83505693b71e785041e67a8bb"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/JoyFeedback.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,79 @@ +#ifndef _ROS_sensor_msgs_JoyFeedback_h +#define _ROS_sensor_msgs_JoyFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class JoyFeedback : public ros::Msg + { + public: + typedef uint8_t _type_type; + _type_type type; + typedef uint8_t _id_type; + _id_type id; + typedef float _intensity_type; + _intensity_type intensity; + enum { TYPE_LED = 0 }; + enum { TYPE_RUMBLE = 1 }; + enum { TYPE_BUZZER = 2 }; + + JoyFeedback(): + type(0), + id(0), + intensity(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; + offset += sizeof(this->type); + *(outbuffer + offset + 0) = (this->id >> (8 * 0)) & 0xFF; + offset += sizeof(this->id); + union { + float real; + uint32_t base; + } u_intensity; + u_intensity.real = this->intensity; + *(outbuffer + offset + 0) = (u_intensity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_intensity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_intensity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_intensity.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->intensity); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->type); + this->id = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->id); + union { + float real; + uint32_t base; + } u_intensity; + u_intensity.base = 0; + u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->intensity = u_intensity.real; + offset += sizeof(this->intensity); + return offset; + } + + const char * getType(){ return "sensor_msgs/JoyFeedback"; }; + const char * getMD5(){ return "f4dcd73460360d98f36e55ee7f2e46f1"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/JoyFeedbackArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_sensor_msgs_JoyFeedbackArray_h +#define _ROS_sensor_msgs_JoyFeedbackArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/JoyFeedback.h" + +namespace sensor_msgs +{ + + class JoyFeedbackArray : public ros::Msg + { + public: + uint32_t array_length; + typedef sensor_msgs::JoyFeedback _array_type; + _array_type st_array; + _array_type * array; + + JoyFeedbackArray(): + array_length(0), array(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->array_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->array_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->array_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->array_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->array_length); + for( uint32_t i = 0; i < array_length; i++){ + offset += this->array[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t array_lengthT = ((uint32_t) (*(inbuffer + offset))); + array_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + array_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + array_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->array_length); + if(array_lengthT > array_length) + this->array = (sensor_msgs::JoyFeedback*)realloc(this->array, array_lengthT * sizeof(sensor_msgs::JoyFeedback)); + array_length = array_lengthT; + for( uint32_t i = 0; i < array_length; i++){ + offset += this->st_array.deserialize(inbuffer + offset); + memcpy( &(this->array[i]), &(this->st_array), sizeof(sensor_msgs::JoyFeedback)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/JoyFeedbackArray"; }; + const char * getMD5(){ return "cde5730a895b1fc4dee6f91b754b213d"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/LaserEcho.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_sensor_msgs_LaserEcho_h +#define _ROS_sensor_msgs_LaserEcho_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class LaserEcho : public ros::Msg + { + public: + uint32_t echoes_length; + typedef float _echoes_type; + _echoes_type st_echoes; + _echoes_type * echoes; + + LaserEcho(): + echoes_length(0), echoes(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->echoes_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->echoes_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->echoes_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->echoes_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->echoes_length); + for( uint32_t i = 0; i < echoes_length; i++){ + union { + float real; + uint32_t base; + } u_echoesi; + u_echoesi.real = this->echoes[i]; + *(outbuffer + offset + 0) = (u_echoesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_echoesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_echoesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_echoesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->echoes[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t echoes_lengthT = ((uint32_t) (*(inbuffer + offset))); + echoes_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + echoes_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + echoes_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->echoes_length); + if(echoes_lengthT > echoes_length) + this->echoes = (float*)realloc(this->echoes, echoes_lengthT * sizeof(float)); + echoes_length = echoes_lengthT; + for( uint32_t i = 0; i < echoes_length; i++){ + union { + float real; + uint32_t base; + } u_st_echoes; + u_st_echoes.base = 0; + u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_echoes = u_st_echoes.real; + offset += sizeof(this->st_echoes); + memcpy( &(this->echoes[i]), &(this->st_echoes), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/LaserEcho"; }; + const char * getMD5(){ return "8bc5ae449b200fba4d552b4225586696"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/LaserScan.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,300 @@ +#ifndef _ROS_sensor_msgs_LaserScan_h +#define _ROS_sensor_msgs_LaserScan_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class LaserScan : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef float _angle_min_type; + _angle_min_type angle_min; + typedef float _angle_max_type; + _angle_max_type angle_max; + typedef float _angle_increment_type; + _angle_increment_type angle_increment; + typedef float _time_increment_type; + _time_increment_type time_increment; + typedef float _scan_time_type; + _scan_time_type scan_time; + typedef float _range_min_type; + _range_min_type range_min; + typedef float _range_max_type; + _range_max_type range_max; + uint32_t ranges_length; + typedef float _ranges_type; + _ranges_type st_ranges; + _ranges_type * ranges; + uint32_t intensities_length; + typedef float _intensities_type; + _intensities_type st_intensities; + _intensities_type * intensities; + + LaserScan(): + header(), + angle_min(0), + angle_max(0), + angle_increment(0), + time_increment(0), + scan_time(0), + range_min(0), + range_max(0), + ranges_length(0), ranges(NULL), + intensities_length(0), intensities(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.real = this->angle_min; + *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.real = this->angle_max; + *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.real = this->angle_increment; + *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.real = this->time_increment; + *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.real = this->scan_time; + *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.real = this->range_min; + *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.real = this->range_max; + *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_max); + *(outbuffer + offset + 0) = (this->ranges_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->ranges_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->ranges_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->ranges_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->ranges_length); + for( uint32_t i = 0; i < ranges_length; i++){ + union { + float real; + uint32_t base; + } u_rangesi; + u_rangesi.real = this->ranges[i]; + *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_rangesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_rangesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->ranges[i]); + } + *(outbuffer + offset + 0) = (this->intensities_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->intensities_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->intensities_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->intensities_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->intensities_length); + for( uint32_t i = 0; i < intensities_length; i++){ + union { + float real; + uint32_t base; + } u_intensitiesi; + u_intensitiesi.real = this->intensities[i]; + *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_intensitiesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_intensitiesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_intensitiesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->intensities[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.base = 0; + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_min = u_angle_min.real; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.base = 0; + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_max = u_angle_max.real; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.base = 0; + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_increment = u_angle_increment.real; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.base = 0; + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->time_increment = u_time_increment.real; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.base = 0; + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->scan_time = u_scan_time.real; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.base = 0; + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_min = u_range_min.real; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.base = 0; + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_max = u_range_max.real; + offset += sizeof(this->range_max); + uint32_t ranges_lengthT = ((uint32_t) (*(inbuffer + offset))); + ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->ranges_length); + if(ranges_lengthT > ranges_length) + this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float)); + ranges_length = ranges_lengthT; + for( uint32_t i = 0; i < ranges_length; i++){ + union { + float real; + uint32_t base; + } u_st_ranges; + u_st_ranges.base = 0; + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_ranges = u_st_ranges.real; + offset += sizeof(this->st_ranges); + memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float)); + } + uint32_t intensities_lengthT = ((uint32_t) (*(inbuffer + offset))); + intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->intensities_length); + if(intensities_lengthT > intensities_length) + this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float)); + intensities_length = intensities_lengthT; + for( uint32_t i = 0; i < intensities_length; i++){ + union { + float real; + uint32_t base; + } u_st_intensities; + u_st_intensities.base = 0; + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_intensities = u_st_intensities.real; + offset += sizeof(this->st_intensities); + memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/LaserScan"; }; + const char * getMD5(){ return "90c7ef2dc6895d81024acba2ac42f369"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/MagneticField.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,85 @@ +#ifndef _ROS_sensor_msgs_MagneticField_h +#define _ROS_sensor_msgs_MagneticField_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Vector3.h" + +namespace sensor_msgs +{ + + class MagneticField : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef geometry_msgs::Vector3 _magnetic_field_type; + _magnetic_field_type magnetic_field; + double magnetic_field_covariance[9]; + + MagneticField(): + header(), + magnetic_field(), + magnetic_field_covariance() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->magnetic_field.serialize(outbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_magnetic_field_covariancei; + u_magnetic_field_covariancei.real = this->magnetic_field_covariance[i]; + *(outbuffer + offset + 0) = (u_magnetic_field_covariancei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_magnetic_field_covariancei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_magnetic_field_covariancei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_magnetic_field_covariancei.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_magnetic_field_covariancei.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_magnetic_field_covariancei.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_magnetic_field_covariancei.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_magnetic_field_covariancei.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->magnetic_field_covariance[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->magnetic_field.deserialize(inbuffer + offset); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_magnetic_field_covariancei; + u_magnetic_field_covariancei.base = 0; + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->magnetic_field_covariance[i] = u_magnetic_field_covariancei.real; + offset += sizeof(this->magnetic_field_covariance[i]); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/MagneticField"; }; + const char * getMD5(){ return "2f3b0b43eed0c9501de0fa3ff89a45aa"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/MultiDOFJointState.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,159 @@ +#ifndef _ROS_sensor_msgs_MultiDOFJointState_h +#define _ROS_sensor_msgs_MultiDOFJointState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Transform.h" +#include "geometry_msgs/Twist.h" +#include "geometry_msgs/Wrench.h" + +namespace sensor_msgs +{ + + class MultiDOFJointState : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + uint32_t joint_names_length; + typedef char* _joint_names_type; + _joint_names_type st_joint_names; + _joint_names_type * joint_names; + uint32_t transforms_length; + typedef geometry_msgs::Transform _transforms_type; + _transforms_type st_transforms; + _transforms_type * transforms; + uint32_t twist_length; + typedef geometry_msgs::Twist _twist_type; + _twist_type st_twist; + _twist_type * twist; + uint32_t wrench_length; + typedef geometry_msgs::Wrench _wrench_type; + _wrench_type st_wrench; + _wrench_type * wrench; + + MultiDOFJointState(): + header(), + joint_names_length(0), joint_names(NULL), + transforms_length(0), transforms(NULL), + twist_length(0), twist(NULL), + wrench_length(0), wrench(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->joint_names_length); + for( uint32_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + varToArr(outbuffer + offset, length_joint_namesi); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + *(outbuffer + offset + 0) = (this->transforms_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->transforms_length); + for( uint32_t i = 0; i < transforms_length; i++){ + offset += this->transforms[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->twist_length); + for( uint32_t i = 0; i < twist_length; i++){ + offset += this->twist[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->wrench_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->wrench_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->wrench_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->wrench_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->wrench_length); + for( uint32_t i = 0; i < wrench_length; i++){ + offset += this->wrench[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); + joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->joint_names_length); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + joint_names_length = joint_names_lengthT; + for( uint32_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + arrToVar(length_st_joint_names, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset))); + transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->transforms_length); + if(transforms_lengthT > transforms_length) + this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform)); + transforms_length = transforms_lengthT; + for( uint32_t i = 0; i < transforms_length; i++){ + offset += this->st_transforms.deserialize(inbuffer + offset); + memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform)); + } + uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); + twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->twist_length); + if(twist_lengthT > twist_length) + this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); + twist_length = twist_lengthT; + for( uint32_t i = 0; i < twist_length; i++){ + offset += this->st_twist.deserialize(inbuffer + offset); + memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); + } + uint32_t wrench_lengthT = ((uint32_t) (*(inbuffer + offset))); + wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->wrench_length); + if(wrench_lengthT > wrench_length) + this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench)); + wrench_length = wrench_lengthT; + for( uint32_t i = 0; i < wrench_length; i++){ + offset += this->st_wrench.deserialize(inbuffer + offset); + memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/MultiDOFJointState"; }; + const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/MultiEchoLaserScan.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,263 @@ +#ifndef _ROS_sensor_msgs_MultiEchoLaserScan_h +#define _ROS_sensor_msgs_MultiEchoLaserScan_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/LaserEcho.h" + +namespace sensor_msgs +{ + + class MultiEchoLaserScan : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef float _angle_min_type; + _angle_min_type angle_min; + typedef float _angle_max_type; + _angle_max_type angle_max; + typedef float _angle_increment_type; + _angle_increment_type angle_increment; + typedef float _time_increment_type; + _time_increment_type time_increment; + typedef float _scan_time_type; + _scan_time_type scan_time; + typedef float _range_min_type; + _range_min_type range_min; + typedef float _range_max_type; + _range_max_type range_max; + uint32_t ranges_length; + typedef sensor_msgs::LaserEcho _ranges_type; + _ranges_type st_ranges; + _ranges_type * ranges; + uint32_t intensities_length; + typedef sensor_msgs::LaserEcho _intensities_type; + _intensities_type st_intensities; + _intensities_type * intensities; + + MultiEchoLaserScan(): + header(), + angle_min(0), + angle_max(0), + angle_increment(0), + time_increment(0), + scan_time(0), + range_min(0), + range_max(0), + ranges_length(0), ranges(NULL), + intensities_length(0), intensities(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.real = this->angle_min; + *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.real = this->angle_max; + *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.real = this->angle_increment; + *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.real = this->time_increment; + *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.real = this->scan_time; + *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.real = this->range_min; + *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.real = this->range_max; + *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_max); + *(outbuffer + offset + 0) = (this->ranges_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->ranges_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->ranges_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->ranges_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->ranges_length); + for( uint32_t i = 0; i < ranges_length; i++){ + offset += this->ranges[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->intensities_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->intensities_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->intensities_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->intensities_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->intensities_length); + for( uint32_t i = 0; i < intensities_length; i++){ + offset += this->intensities[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.base = 0; + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_min = u_angle_min.real; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.base = 0; + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_max = u_angle_max.real; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.base = 0; + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_increment = u_angle_increment.real; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.base = 0; + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->time_increment = u_time_increment.real; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.base = 0; + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->scan_time = u_scan_time.real; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.base = 0; + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_min = u_range_min.real; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.base = 0; + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_max = u_range_max.real; + offset += sizeof(this->range_max); + uint32_t ranges_lengthT = ((uint32_t) (*(inbuffer + offset))); + ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->ranges_length); + if(ranges_lengthT > ranges_length) + this->ranges = (sensor_msgs::LaserEcho*)realloc(this->ranges, ranges_lengthT * sizeof(sensor_msgs::LaserEcho)); + ranges_length = ranges_lengthT; + for( uint32_t i = 0; i < ranges_length; i++){ + offset += this->st_ranges.deserialize(inbuffer + offset); + memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(sensor_msgs::LaserEcho)); + } + uint32_t intensities_lengthT = ((uint32_t) (*(inbuffer + offset))); + intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->intensities_length); + if(intensities_lengthT > intensities_length) + this->intensities = (sensor_msgs::LaserEcho*)realloc(this->intensities, intensities_lengthT * sizeof(sensor_msgs::LaserEcho)); + intensities_length = intensities_lengthT; + for( uint32_t i = 0; i < intensities_length; i++){ + offset += this->st_intensities.deserialize(inbuffer + offset); + memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(sensor_msgs::LaserEcho)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/MultiEchoLaserScan"; }; + const char * getMD5(){ return "6fefb0c6da89d7c8abe4b339f5c2f8fb"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/NavSatFix.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,192 @@ +#ifndef _ROS_sensor_msgs_NavSatFix_h +#define _ROS_sensor_msgs_NavSatFix_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/NavSatStatus.h" + +namespace sensor_msgs +{ + + class NavSatFix : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef sensor_msgs::NavSatStatus _status_type; + _status_type status; + typedef double _latitude_type; + _latitude_type latitude; + typedef double _longitude_type; + _longitude_type longitude; + typedef double _altitude_type; + _altitude_type altitude; + double position_covariance[9]; + typedef uint8_t _position_covariance_type_type; + _position_covariance_type_type position_covariance_type; + enum { COVARIANCE_TYPE_UNKNOWN = 0 }; + enum { COVARIANCE_TYPE_APPROXIMATED = 1 }; + enum { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 }; + enum { COVARIANCE_TYPE_KNOWN = 3 }; + + NavSatFix(): + header(), + status(), + latitude(0), + longitude(0), + altitude(0), + position_covariance(), + position_covariance_type(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + union { + double real; + uint64_t base; + } u_latitude; + u_latitude.real = this->latitude; + *(outbuffer + offset + 0) = (u_latitude.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_latitude.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_latitude.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_latitude.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_latitude.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_latitude.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_latitude.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_latitude.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->latitude); + union { + double real; + uint64_t base; + } u_longitude; + u_longitude.real = this->longitude; + *(outbuffer + offset + 0) = (u_longitude.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_longitude.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_longitude.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_longitude.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_longitude.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_longitude.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_longitude.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_longitude.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->longitude); + union { + double real; + uint64_t base; + } u_altitude; + u_altitude.real = this->altitude; + *(outbuffer + offset + 0) = (u_altitude.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_altitude.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_altitude.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_altitude.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_altitude.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_altitude.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_altitude.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_altitude.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->altitude); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_position_covariancei; + u_position_covariancei.real = this->position_covariance[i]; + *(outbuffer + offset + 0) = (u_position_covariancei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_position_covariancei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_position_covariancei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_position_covariancei.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_position_covariancei.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_position_covariancei.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_position_covariancei.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_position_covariancei.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->position_covariance[i]); + } + *(outbuffer + offset + 0) = (this->position_covariance_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->position_covariance_type); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + union { + double real; + uint64_t base; + } u_latitude; + u_latitude.base = 0; + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->latitude = u_latitude.real; + offset += sizeof(this->latitude); + union { + double real; + uint64_t base; + } u_longitude; + u_longitude.base = 0; + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->longitude = u_longitude.real; + offset += sizeof(this->longitude); + union { + double real; + uint64_t base; + } u_altitude; + u_altitude.base = 0; + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->altitude = u_altitude.real; + offset += sizeof(this->altitude); + for( uint32_t i = 0; i < 9; i++){ + union { + double real; + uint64_t base; + } u_position_covariancei; + u_position_covariancei.base = 0; + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->position_covariance[i] = u_position_covariancei.real; + offset += sizeof(this->position_covariance[i]); + } + this->position_covariance_type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->position_covariance_type); + return offset; + } + + const char * getType(){ return "sensor_msgs/NavSatFix"; }; + const char * getMD5(){ return "2d3a8cd499b9b4a0249fb98fd05cfa48"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/NavSatStatus.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,73 @@ +#ifndef _ROS_sensor_msgs_NavSatStatus_h +#define _ROS_sensor_msgs_NavSatStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class NavSatStatus : public ros::Msg + { + public: + typedef int8_t _status_type; + _status_type status; + typedef uint16_t _service_type; + _service_type service; + enum { STATUS_NO_FIX = -1 }; + enum { STATUS_FIX = 0 }; + enum { STATUS_SBAS_FIX = 1 }; + enum { STATUS_GBAS_FIX = 2 }; + enum { SERVICE_GPS = 1 }; + enum { SERVICE_GLONASS = 2 }; + enum { SERVICE_COMPASS = 4 }; + enum { SERVICE_GALILEO = 8 }; + + NavSatStatus(): + status(0), + service(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_status; + u_status.real = this->status; + *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->status); + *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF; + offset += sizeof(this->service); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_status; + u_status.base = 0; + u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->status = u_status.real; + offset += sizeof(this->status); + this->service = ((uint16_t) (*(inbuffer + offset))); + this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->service); + return offset; + } + + const char * getType(){ return "sensor_msgs/NavSatStatus"; }; + const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointCloud.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_sensor_msgs_PointCloud_h +#define _ROS_sensor_msgs_PointCloud_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point32.h" +#include "sensor_msgs/ChannelFloat32.h" + +namespace sensor_msgs +{ + + class PointCloud : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + uint32_t points_length; + typedef geometry_msgs::Point32 _points_type; + _points_type st_points; + _points_type * points; + uint32_t channels_length; + typedef sensor_msgs::ChannelFloat32 _channels_type; + _channels_type st_channels; + _channels_type * channels; + + PointCloud(): + header(), + points_length(0), points(NULL), + channels_length(0), channels(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->points_length); + for( uint32_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->channels_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->channels_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->channels_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->channels_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->channels_length); + for( uint32_t i = 0; i < channels_length; i++){ + offset += this->channels[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); + points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->points_length); + if(points_lengthT > points_length) + this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32)); + points_length = points_lengthT; + for( uint32_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32)); + } + uint32_t channels_lengthT = ((uint32_t) (*(inbuffer + offset))); + channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->channels_length); + if(channels_lengthT > channels_length) + this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32)); + channels_length = channels_lengthT; + for( uint32_t i = 0; i < channels_length; i++){ + offset += this->st_channels.deserialize(inbuffer + offset); + memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/PointCloud"; }; + const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointCloud2.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,185 @@ +#ifndef _ROS_sensor_msgs_PointCloud2_h +#define _ROS_sensor_msgs_PointCloud2_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/PointField.h" + +namespace sensor_msgs +{ + + class PointCloud2 : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef uint32_t _height_type; + _height_type height; + typedef uint32_t _width_type; + _width_type width; + uint32_t fields_length; + typedef sensor_msgs::PointField _fields_type; + _fields_type st_fields; + _fields_type * fields; + typedef bool _is_bigendian_type; + _is_bigendian_type is_bigendian; + typedef uint32_t _point_step_type; + _point_step_type point_step; + typedef uint32_t _row_step_type; + _row_step_type row_step; + uint32_t data_length; + typedef uint8_t _data_type; + _data_type st_data; + _data_type * data; + typedef bool _is_dense_type; + _is_dense_type is_dense; + + PointCloud2(): + header(), + height(0), + width(0), + fields_length(0), fields(NULL), + is_bigendian(0), + point_step(0), + row_step(0), + data_length(0), data(NULL), + is_dense(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + *(outbuffer + offset + 0) = (this->fields_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->fields_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->fields_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->fields_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->fields_length); + for( uint32_t i = 0; i < fields_length; i++){ + offset += this->fields[i].serialize(outbuffer + offset); + } + union { + bool real; + uint8_t base; + } u_is_bigendian; + u_is_bigendian.real = this->is_bigendian; + *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_bigendian); + *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF; + offset += sizeof(this->point_step); + *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF; + offset += sizeof(this->row_step); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + union { + bool real; + uint8_t base; + } u_is_dense; + u_is_dense.real = this->is_dense; + *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_dense); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint32_t fields_lengthT = ((uint32_t) (*(inbuffer + offset))); + fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->fields_length); + if(fields_lengthT > fields_length) + this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField)); + fields_length = fields_lengthT; + for( uint32_t i = 0; i < fields_length; i++){ + offset += this->st_fields.deserialize(inbuffer + offset); + memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField)); + } + union { + bool real; + uint8_t base; + } u_is_bigendian; + u_is_bigendian.base = 0; + u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_bigendian = u_is_bigendian.real; + offset += sizeof(this->is_bigendian); + this->point_step = ((uint32_t) (*(inbuffer + offset))); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->point_step); + this->row_step = ((uint32_t) (*(inbuffer + offset))); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->row_step); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + union { + bool real; + uint8_t base; + } u_is_dense; + u_is_dense.base = 0; + u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_dense = u_is_dense.real; + offset += sizeof(this->is_dense); + return offset; + } + + const char * getType(){ return "sensor_msgs/PointCloud2"; }; + const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointField.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_sensor_msgs_PointField_h +#define _ROS_sensor_msgs_PointField_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class PointField : public ros::Msg + { + public: + typedef const char* _name_type; + _name_type name; + typedef uint32_t _offset_type; + _offset_type offset; + typedef uint8_t _datatype_type; + _datatype_type datatype; + typedef uint32_t _count_type; + _count_type count; + enum { INT8 = 1 }; + enum { UINT8 = 2 }; + enum { INT16 = 3 }; + enum { UINT16 = 4 }; + enum { INT32 = 5 }; + enum { UINT32 = 6 }; + enum { FLOAT32 = 7 }; + enum { FLOAT64 = 8 }; + + PointField(): + name(""), + offset(0), + datatype(0), + count(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + varToArr(outbuffer + offset, length_name); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->offset); + *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF; + offset += sizeof(this->datatype); + *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF; + offset += sizeof(this->count); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + arrToVar(length_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + this->offset = ((uint32_t) (*(inbuffer + offset))); + this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->offset); + this->datatype = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->datatype); + this->count = ((uint32_t) (*(inbuffer + offset))); + this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->count); + return offset; + } + + const char * getType(){ return "sensor_msgs/PointField"; }; + const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Range.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,149 @@ +#ifndef _ROS_sensor_msgs_Range_h +#define _ROS_sensor_msgs_Range_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Range : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef uint8_t _radiation_type_type; + _radiation_type_type radiation_type; + typedef float _field_of_view_type; + _field_of_view_type field_of_view; + typedef float _min_range_type; + _min_range_type min_range; + typedef float _max_range_type; + _max_range_type max_range; + typedef float _range_type; + _range_type range; + enum { ULTRASOUND = 0 }; + enum { INFRARED = 1 }; + + Range(): + header(), + radiation_type(0), + field_of_view(0), + min_range(0), + max_range(0), + range(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->radiation_type); + union { + float real; + uint32_t base; + } u_field_of_view; + u_field_of_view.real = this->field_of_view; + *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->field_of_view); + union { + float real; + uint32_t base; + } u_min_range; + u_min_range.real = this->min_range; + *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_range); + union { + float real; + uint32_t base; + } u_max_range; + u_max_range.real = this->max_range; + *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_range); + union { + float real; + uint32_t base; + } u_range; + u_range.real = this->range; + *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->radiation_type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->radiation_type); + union { + float real; + uint32_t base; + } u_field_of_view; + u_field_of_view.base = 0; + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->field_of_view = u_field_of_view.real; + offset += sizeof(this->field_of_view); + union { + float real; + uint32_t base; + } u_min_range; + u_min_range.base = 0; + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->min_range = u_min_range.real; + offset += sizeof(this->min_range); + union { + float real; + uint32_t base; + } u_max_range; + u_max_range.base = 0; + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->max_range = u_max_range.real; + offset += sizeof(this->max_range); + union { + float real; + uint32_t base; + } u_range; + u_range.base = 0; + u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range = u_range.real; + offset += sizeof(this->range); + return offset; + } + + const char * getType(){ return "sensor_msgs/Range"; }; + const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/RegionOfInterest.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,108 @@ +#ifndef _ROS_sensor_msgs_RegionOfInterest_h +#define _ROS_sensor_msgs_RegionOfInterest_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class RegionOfInterest : public ros::Msg + { + public: + typedef uint32_t _x_offset_type; + _x_offset_type x_offset; + typedef uint32_t _y_offset_type; + _y_offset_type y_offset; + typedef uint32_t _height_type; + _height_type height; + typedef uint32_t _width_type; + _width_type width; + typedef bool _do_rectify_type; + _do_rectify_type do_rectify; + + RegionOfInterest(): + x_offset(0), + y_offset(0), + height(0), + width(0), + do_rectify(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->x_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->x_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->x_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->x_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->x_offset); + *(outbuffer + offset + 0) = (this->y_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->y_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->y_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->y_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->y_offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + union { + bool real; + uint8_t base; + } u_do_rectify; + u_do_rectify.real = this->do_rectify; + *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->do_rectify); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->x_offset = ((uint32_t) (*(inbuffer + offset))); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->x_offset); + this->y_offset = ((uint32_t) (*(inbuffer + offset))); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->y_offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + union { + bool real; + uint8_t base; + } u_do_rectify; + u_do_rectify.base = 0; + u_do_rectify.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->do_rectify = u_do_rectify.real; + offset += sizeof(this->do_rectify); + return offset; + } + + const char * getType(){ return "sensor_msgs/RegionOfInterest"; }; + const char * getMD5(){ return "bdb633039d588fcccb441a4d43ccfe09"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/RelativeHumidity.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,108 @@ +#ifndef _ROS_sensor_msgs_RelativeHumidity_h +#define _ROS_sensor_msgs_RelativeHumidity_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class RelativeHumidity : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef double _relative_humidity_type; + _relative_humidity_type relative_humidity; + typedef double _variance_type; + _variance_type variance; + + RelativeHumidity(): + header(), + relative_humidity(0), + variance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + double real; + uint64_t base; + } u_relative_humidity; + u_relative_humidity.real = this->relative_humidity; + *(outbuffer + offset + 0) = (u_relative_humidity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_relative_humidity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_relative_humidity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_relative_humidity.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_relative_humidity.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_relative_humidity.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_relative_humidity.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_relative_humidity.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->relative_humidity); + union { + double real; + uint64_t base; + } u_variance; + u_variance.real = this->variance; + *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->variance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + double real; + uint64_t base; + } u_relative_humidity; + u_relative_humidity.base = 0; + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->relative_humidity = u_relative_humidity.real; + offset += sizeof(this->relative_humidity); + union { + double real; + uint64_t base; + } u_variance; + u_variance.base = 0; + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->variance = u_variance.real; + offset += sizeof(this->variance); + return offset; + } + + const char * getType(){ return "sensor_msgs/RelativeHumidity"; }; + const char * getMD5(){ return "8730015b05955b7e992ce29a2678d90f"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/SetCameraInfo.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,111 @@ +#ifndef _ROS_SERVICE_SetCameraInfo_h +#define _ROS_SERVICE_SetCameraInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/CameraInfo.h" + +namespace sensor_msgs +{ + +static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo"; + + class SetCameraInfoRequest : public ros::Msg + { + public: + typedef sensor_msgs::CameraInfo _camera_info_type; + _camera_info_type camera_info; + + SetCameraInfoRequest(): + camera_info() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->camera_info.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->camera_info.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETCAMERAINFO; }; + const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; }; + + }; + + class SetCameraInfoResponse : public ros::Msg + { + public: + typedef bool _success_type; + _success_type success; + typedef const char* _status_message_type; + _status_message_type status_message; + + SetCameraInfoResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + varToArr(outbuffer + offset, length_status_message); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + arrToVar(length_status_message, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETCAMERAINFO; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetCameraInfo { + public: + typedef SetCameraInfoRequest Request; + typedef SetCameraInfoResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Temperature.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,108 @@ +#ifndef _ROS_sensor_msgs_Temperature_h +#define _ROS_sensor_msgs_Temperature_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Temperature : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef double _temperature_type; + _temperature_type temperature; + typedef double _variance_type; + _variance_type variance; + + Temperature(): + header(), + temperature(0), + variance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + double real; + uint64_t base; + } u_temperature; + u_temperature.real = this->temperature; + *(outbuffer + offset + 0) = (u_temperature.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_temperature.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_temperature.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_temperature.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_temperature.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_temperature.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_temperature.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_temperature.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->temperature); + union { + double real; + uint64_t base; + } u_variance; + u_variance.real = this->variance; + *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->variance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + double real; + uint64_t base; + } u_temperature; + u_temperature.base = 0; + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->temperature = u_temperature.real; + offset += sizeof(this->temperature); + union { + double real; + uint64_t base; + } u_variance; + u_variance.base = 0; + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->variance = u_variance.real; + offset += sizeof(this->variance); + return offset; + } + + const char * getType(){ return "sensor_msgs/Temperature"; }; + const char * getMD5(){ return "ff71b307acdbe7c871a5a6d7ed359100"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/TimeReference.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,85 @@ +#ifndef _ROS_sensor_msgs_TimeReference_h +#define _ROS_sensor_msgs_TimeReference_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "ros/time.h" + +namespace sensor_msgs +{ + + class TimeReference : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef ros::Time _time_ref_type; + _time_ref_type time_ref; + typedef const char* _source_type; + _source_type source; + + TimeReference(): + header(), + time_ref(), + source("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->time_ref.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_ref.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_ref.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_ref.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_ref.sec); + *(outbuffer + offset + 0) = (this->time_ref.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_ref.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_ref.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_ref.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_ref.nsec); + uint32_t length_source = strlen(this->source); + varToArr(outbuffer + offset, length_source); + offset += 4; + memcpy(outbuffer + offset, this->source, length_source); + offset += length_source; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->time_ref.sec = ((uint32_t) (*(inbuffer + offset))); + this->time_ref.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_ref.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_ref.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_ref.sec); + this->time_ref.nsec = ((uint32_t) (*(inbuffer + offset))); + this->time_ref.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_ref.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_ref.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_ref.nsec); + uint32_t length_source; + arrToVar(length_source, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_source; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_source-1]=0; + this->source = (char *)(inbuffer + offset-1); + offset += length_source; + return offset; + } + + const char * getType(){ return "sensor_msgs/TimeReference"; }; + const char * getMD5(){ return "fded64a0265108ba86c3d38fb11c0c16"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Bool.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Bool_h +#define _ROS_std_msgs_Bool_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Bool : public ros::Msg + { + public: + typedef bool _data_type; + _data_type data; + + Bool(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Bool"; }; + const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Byte.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Byte_h +#define _ROS_std_msgs_Byte_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Byte : public ros::Msg + { + public: + typedef int8_t _data_type; + _data_type data; + + Byte(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Byte"; }; + const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ByteMultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_std_msgs_ByteMultiArray_h +#define _ROS_std_msgs_ByteMultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class ByteMultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef int8_t _data_type; + _data_type st_data; + _data_type * data; + + ByteMultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/ByteMultiArray"; }; + const char * getMD5(){ return "70ea476cbcfd65ac2f68f3cda1e891fe"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Char.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,45 @@ +#ifndef _ROS_std_msgs_Char_h +#define _ROS_std_msgs_Char_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Char : public ros::Msg + { + public: + typedef uint8_t _data_type; + _data_type data; + + Char(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Char"; }; + const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ColorRGBA.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,134 @@ +#ifndef _ROS_std_msgs_ColorRGBA_h +#define _ROS_std_msgs_ColorRGBA_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class ColorRGBA : public ros::Msg + { + public: + typedef float _r_type; + _r_type r; + typedef float _g_type; + _g_type g; + typedef float _b_type; + _b_type b; + typedef float _a_type; + _a_type a; + + ColorRGBA(): + r(0), + g(0), + b(0), + a(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.real = this->r; + *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.real = this->g; + *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->a); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.base = 0; + u_r.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->r = u_r.real; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.base = 0; + u_g.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->g = u_g.real; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->b = u_b.real; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->a = u_a.real; + offset += sizeof(this->a); + return offset; + } + + const char * getType(){ return "std_msgs/ColorRGBA"; }; + const char * getMD5(){ return "a29a96539573343b1310c73607334b00"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Duration.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,62 @@ +#ifndef _ROS_std_msgs_Duration_h +#define _ROS_std_msgs_Duration_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" + +namespace std_msgs +{ + + class Duration : public ros::Msg + { + public: + typedef ros::Duration _data_type; + _data_type data; + + Duration(): + data() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.sec); + *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data.sec = ((uint32_t) (*(inbuffer + offset))); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.sec); + this->data.nsec = ((uint32_t) (*(inbuffer + offset))); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.nsec); + return offset; + } + + const char * getType(){ return "std_msgs/Duration"; }; + const char * getMD5(){ return "3e286caf4241d664e55f3ad380e2ae46"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Empty.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_std_msgs_Empty_h +#define _ROS_std_msgs_Empty_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Empty : public ros::Msg + { + public: + + Empty() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "std_msgs/Empty"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,62 @@ +#ifndef _ROS_std_msgs_Float32_h +#define _ROS_std_msgs_Float32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float32 : public ros::Msg + { + public: + typedef float _data_type; + _data_type data; + + Float32(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Float32"; }; + const char * getMD5(){ return "73fcbf46b49191e672908e50842a83d4"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,88 @@ +#ifndef _ROS_std_msgs_Float32MultiArray_h +#define _ROS_std_msgs_Float32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float32MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef float _data_type; + _data_type st_data; + _data_type * data; + + Float32MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float32MultiArray"; }; + const char * getMD5(){ return "6a40e0ffa6a17a503ac3f8616991b1f6"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_std_msgs_Float64_h +#define _ROS_std_msgs_Float64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float64 : public ros::Msg + { + public: + typedef double _data_type; + _data_type data; + + Float64(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + double real; + uint64_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + double real; + uint64_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Float64"; }; + const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_std_msgs_Float64MultiArray_h +#define _ROS_std_msgs_Float64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float64MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef double _data_type; + _data_type st_data; + _data_type * data; + + Float64MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + double real; + uint64_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (double*)realloc(this->data, data_lengthT * sizeof(double)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + double real; + uint64_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(double)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float64MultiArray"; }; + const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Header.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_std_msgs_Header_h +#define _ROS_std_msgs_Header_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace std_msgs +{ + + class Header : public ros::Msg + { + public: + typedef uint32_t _seq_type; + _seq_type seq; + typedef ros::Time _stamp_type; + _stamp_type stamp; + typedef const char* _frame_id_type; + _frame_id_type frame_id; + + Header(): + seq(0), + stamp(), + frame_id("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF; + offset += sizeof(this->seq); + *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.sec); + *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id = strlen(this->frame_id); + varToArr(outbuffer + offset, length_frame_id); + offset += 4; + memcpy(outbuffer + offset, this->frame_id, length_frame_id); + offset += length_frame_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->seq = ((uint32_t) (*(inbuffer + offset))); + this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->seq); + this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.sec); + this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id; + arrToVar(length_frame_id, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_frame_id-1]=0; + this->frame_id = (char *)(inbuffer + offset-1); + offset += length_frame_id; + return offset; + } + + const char * getType(){ return "std_msgs/Header"; }; + const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_std_msgs_Int16_h +#define _ROS_std_msgs_Int16_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int16 : public ros::Msg + { + public: + typedef int16_t _data_type; + _data_type data; + + Int16(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int16"; }; + const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_std_msgs_Int16MultiArray_h +#define _ROS_std_msgs_Int16MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int16MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef int16_t _data_type; + _data_type st_data; + _data_type * data; + + Int16MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int16MultiArray"; }; + const char * getMD5(){ return "d9338d7f523fcb692fae9d0a0e9f067c"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,62 @@ +#ifndef _ROS_std_msgs_Int32_h +#define _ROS_std_msgs_Int32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int32 : public ros::Msg + { + public: + typedef int32_t _data_type; + _data_type data; + + Int32(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int32"; }; + const char * getMD5(){ return "da5909fbe378aeaf85e547e830cc1bb7"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,88 @@ +#ifndef _ROS_std_msgs_Int32MultiArray_h +#define _ROS_std_msgs_Int32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int32MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef int32_t _data_type; + _data_type st_data; + _data_type * data; + + Int32MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int32MultiArray"; }; + const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_std_msgs_Int64_h +#define _ROS_std_msgs_Int64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int64 : public ros::Msg + { + public: + typedef int64_t _data_type; + _data_type data; + + Int64(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int64"; }; + const char * getMD5(){ return "34add168574510e6e17f5d23ecc077ef"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_std_msgs_Int64MultiArray_h +#define _ROS_std_msgs_Int64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int64MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef int64_t _data_type; + _data_type st_data; + _data_type * data; + + Int64MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int64MultiArray"; }; + const char * getMD5(){ return "54865aa6c65be0448113a2afc6a49270"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Int8_h +#define _ROS_std_msgs_Int8_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int8 : public ros::Msg + { + public: + typedef int8_t _data_type; + _data_type data; + + Int8(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int8"; }; + const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_std_msgs_Int8MultiArray_h +#define _ROS_std_msgs_Int8MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int8MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef int8_t _data_type; + _data_type st_data; + _data_type * data; + + Int8MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int8MultiArray"; }; + const char * getMD5(){ return "d7c1af35a1b4781bbe79e03dd94b7c13"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/MultiArrayDimension.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,81 @@ +#ifndef _ROS_std_msgs_MultiArrayDimension_h +#define _ROS_std_msgs_MultiArrayDimension_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class MultiArrayDimension : public ros::Msg + { + public: + typedef const char* _label_type; + _label_type label; + typedef uint32_t _size_type; + _size_type size; + typedef uint32_t _stride_type; + _stride_type stride; + + MultiArrayDimension(): + label(""), + size(0), + stride(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_label = strlen(this->label); + varToArr(outbuffer + offset, length_label); + offset += 4; + memcpy(outbuffer + offset, this->label, length_label); + offset += length_label; + *(outbuffer + offset + 0) = (this->size >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->size >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->size >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->size >> (8 * 3)) & 0xFF; + offset += sizeof(this->size); + *(outbuffer + offset + 0) = (this->stride >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stride >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stride >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stride >> (8 * 3)) & 0xFF; + offset += sizeof(this->stride); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_label; + arrToVar(length_label, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_label; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_label-1]=0; + this->label = (char *)(inbuffer + offset-1); + offset += length_label; + this->size = ((uint32_t) (*(inbuffer + offset))); + this->size |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->size |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->size |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->size); + this->stride = ((uint32_t) (*(inbuffer + offset))); + this->stride |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stride |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stride |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stride); + return offset; + } + + const char * getType(){ return "std_msgs/MultiArrayDimension"; }; + const char * getMD5(){ return "4cd0c83a8683deae40ecdac60e53bfa8"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/MultiArrayLayout.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,77 @@ +#ifndef _ROS_std_msgs_MultiArrayLayout_h +#define _ROS_std_msgs_MultiArrayLayout_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayDimension.h" + +namespace std_msgs +{ + + class MultiArrayLayout : public ros::Msg + { + public: + uint32_t dim_length; + typedef std_msgs::MultiArrayDimension _dim_type; + _dim_type st_dim; + _dim_type * dim; + typedef uint32_t _data_offset_type; + _data_offset_type data_offset; + + MultiArrayLayout(): + dim_length(0), dim(NULL), + data_offset(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->dim_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->dim_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->dim_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->dim_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->dim_length); + for( uint32_t i = 0; i < dim_length; i++){ + offset += this->dim[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->data_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t dim_lengthT = ((uint32_t) (*(inbuffer + offset))); + dim_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + dim_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + dim_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->dim_length); + if(dim_lengthT > dim_length) + this->dim = (std_msgs::MultiArrayDimension*)realloc(this->dim, dim_lengthT * sizeof(std_msgs::MultiArrayDimension)); + dim_length = dim_lengthT; + for( uint32_t i = 0; i < dim_length; i++){ + offset += this->st_dim.deserialize(inbuffer + offset); + memcpy( &(this->dim[i]), &(this->st_dim), sizeof(std_msgs::MultiArrayDimension)); + } + this->data_offset = ((uint32_t) (*(inbuffer + offset))); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_offset); + return offset; + } + + const char * getType(){ return "std_msgs/MultiArrayLayout"; }; + const char * getMD5(){ return "0fed2a11c13e11c5571b4e2a995a91a3"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/String.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,55 @@ +#ifndef _ROS_std_msgs_String_h +#define _ROS_std_msgs_String_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class String : public ros::Msg + { + public: + typedef const char* _data_type; + _data_type data; + + String(): + data("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_data = strlen(this->data); + varToArr(outbuffer + offset, length_data); + offset += 4; + memcpy(outbuffer + offset, this->data, length_data); + offset += length_data; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_data; + arrToVar(length_data, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_data; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_data-1]=0; + this->data = (char *)(inbuffer + offset-1); + offset += length_data; + return offset; + } + + const char * getType(){ return "std_msgs/String"; }; + const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Time.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,62 @@ +#ifndef _ROS_std_msgs_Time_h +#define _ROS_std_msgs_Time_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace std_msgs +{ + + class Time : public ros::Msg + { + public: + typedef ros::Time _data_type; + _data_type data; + + Time(): + data() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.sec); + *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data.sec = ((uint32_t) (*(inbuffer + offset))); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.sec); + this->data.nsec = ((uint32_t) (*(inbuffer + offset))); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.nsec); + return offset; + } + + const char * getType(){ return "std_msgs/Time"; }; + const char * getMD5(){ return "cd7166c74c552c311fbcc2fe5a7bc289"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt16.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,47 @@ +#ifndef _ROS_std_msgs_UInt16_h +#define _ROS_std_msgs_UInt16_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt16 : public ros::Msg + { + public: + typedef uint16_t _data_type; + _data_type data; + + UInt16(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint16_t) (*(inbuffer + offset))); + this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt16"; }; + const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt16MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,73 @@ +#ifndef _ROS_std_msgs_UInt16MultiArray_h +#define _ROS_std_msgs_UInt16MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt16MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef uint16_t _data_type; + _data_type st_data; + _data_type * data; + + UInt16MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (uint16_t*)realloc(this->data, data_lengthT * sizeof(uint16_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + this->st_data = ((uint16_t) (*(inbuffer + offset))); + this->st_data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint16_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt16MultiArray"; }; + const char * getMD5(){ return "52f264f1c973c4b73790d384c6cb4484"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt32.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,51 @@ +#ifndef _ROS_std_msgs_UInt32_h +#define _ROS_std_msgs_UInt32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt32 : public ros::Msg + { + public: + typedef uint32_t _data_type; + _data_type data; + + UInt32(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint32_t) (*(inbuffer + offset))); + this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt32"; }; + const char * getMD5(){ return "304a39449588c7f8ce2df6e8001c5fce"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt32MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,77 @@ +#ifndef _ROS_std_msgs_UInt32MultiArray_h +#define _ROS_std_msgs_UInt32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt32MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef uint32_t _data_type; + _data_type st_data; + _data_type * data; + + UInt32MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + this->st_data = ((uint32_t) (*(inbuffer + offset))); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt32MultiArray"; }; + const char * getMD5(){ return "4d6a180abc9be191b96a7eda6c8a233d"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt64.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,62 @@ +#ifndef _ROS_std_msgs_UInt64_h +#define _ROS_std_msgs_UInt64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt64 : public ros::Msg + { + public: + typedef uint64_t _data_type; + _data_type data; + + UInt64(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + uint64_t real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + uint64_t real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt64"; }; + const char * getMD5(){ return "1b2a79973e8bf53d7b53acb71299cb57"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt64MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,88 @@ +#ifndef _ROS_std_msgs_UInt64MultiArray_h +#define _ROS_std_msgs_UInt64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt64MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef uint64_t _data_type; + _data_type st_data; + _data_type * data; + + UInt64MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + union { + uint64_t real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (uint64_t*)realloc(this->data, data_lengthT * sizeof(uint64_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + union { + uint64_t real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint64_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt64MultiArray"; }; + const char * getMD5(){ return "6088f127afb1d6c72927aa1247e945af"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt8.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,45 @@ +#ifndef _ROS_std_msgs_UInt8_h +#define _ROS_std_msgs_UInt8_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt8 : public ros::Msg + { + public: + typedef uint8_t _data_type; + _data_type data; + + UInt8(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt8"; }; + const char * getMD5(){ return "7c8164229e7d2c17eb95e9231617fdee"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt8MultiArray.h Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_std_msgs_UInt8MultiArray_h +#define _ROS_std_msgs_UInt8MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt8MultiArray : public ros::Msg + { + public: + typedef std_msgs::MultiArrayLayout _layout_type; + _layout_type layout; + uint32_t data_length; + typedef uint8_t _data_type; + _data_type st_data; + _data_type * data; + + UInt8MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_length); + for( uint32_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_length); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + data_length = data_lengthT; + for( uint32_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt8MultiArray"; }; + const char * getMD5(){ return "82373f1612381bb6ee473b5cd6f5d89c"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/time.cpp Tue Aug 13 05:53:22 2019 +0000 @@ -0,0 +1,68 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "ros/time.h" + +namespace ros +{ + void normalizeSecNSec(uint32_t& sec, uint32_t& nsec){ + uint32_t nsec_part= nsec % 1000000000UL; + uint32_t sec_part = nsec / 1000000000UL; + sec += sec_part; + nsec = nsec_part; + } + + Time& Time::fromNSec(int32_t t) + { + sec = t / 1000000000; + nsec = t % 1000000000; + normalizeSecNSec(sec, nsec); + return *this; + } + + Time& Time::operator +=(const Duration &rhs) + { + sec += rhs.sec; + nsec += rhs.nsec; + normalizeSecNSec(sec, nsec); + return *this; + } + + Time& Time::operator -=(const Duration &rhs){ + sec += -rhs.sec; + nsec += -rhs.nsec; + normalizeSecNSec(sec, nsec); + return *this; + } +}