Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: BufferedSerial sn7544
Fork of GPG_motor by
Revision 7:13dd93a0efe8, committed 2019-06-27
- Comitter:
- Jeonghoon
- Date:
- Thu Jun 27 04:58:29 2019 +0000
- Parent:
- 6:2478c5817b47
- Child:
- 8:efe5a5b1f10a
- Commit message:
- combine motor with ROS
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/BufferedSerial.lib Thu Jun 27 04:58:29 2019 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/sam_grove/code/BufferedSerial/#a0d37088b405
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MbedHardware.h Thu Jun 27 04:58:29 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 Thu Jun 27 04:08:38 2019 +0000
+++ b/main.cpp Thu Jun 27 04:58:29 2019 +0000
@@ -1,10 +1,25 @@
#include "mbed.h"
#include "motor.h"
+#include <ros.h>
+#include <std_msgs/Float64.h>
+#include <std_msgs/Float32.h>
+#include <std_msgs/Int32.h>
+
+std_msgs::Float64 cum_dist;
+std_msgs::Float32 rela_dist;
+std_msgs::Int32 curr_rpm;
+
+
+ros::NodeHandle nh ;
+ros::Publisher cum_dist_pub("cum_dist", &cum_dist);
+ros::Publisher rela_dist_pub("rela_dist", &rela_dist);
+ros::Publisher rpm_pub("rpm", &curr_rpm);
MotorCtl motor1(D3,D12,D4,D5);
InterruptIn tachoINT1(D4);
InterruptIn tachoINT2(D5);
Serial pc(USBTX,USBRX,115200);
+
char rx_buffer[10];
int index=0;
volatile int flag;
@@ -45,6 +60,11 @@
int main()
{
+ nh.initNode();
+ nh.advertise(cum_dist_pub);
+ nh.advertise(rela_dist_pub);
+ nh.advertise(rpm_pub);
+
tachoINT1.fall(&update_current);
tachoINT1.rise(&update_current);
tachoINT2.fall(&update_current);
@@ -62,9 +82,17 @@
rpm = motor1.getRPM();
cumdistance = motor1.CalculateCumDis(); // 누적거리
reladistance = motor1.CalculateRelaDis(); // 상대거리
-
-
- printf("Rpm: %f\r\n",distance);
+
+ cum_dist.data = cumdistance;
+ cum_dist_pub.publish(&cum_dist);
+
+ rela_dist.data = reladistance;
+ rela_dist_pub.publish(&rela_dist);
+
+ curr_rpm.data = rpm;
+ rpm_pub.publish(&curr_rpm);
+
+ printf("Rpm: %f\r\n",rpm);
printf("cumdistance: %f\r\n",cumdistance);
printf("reladistance: %f\r\n",reladistance);
wait(1);
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/ros.h Thu Jun 27 04:58:29 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/duration.h Thu Jun 27 04:58:29 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/msg.h Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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/service_client.h Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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/rosserial_msgs/Log.h Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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/std_msgs/Bool.h Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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 Thu Jun 27 04:58:29 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;
+ }
+}
