ros melodic library with custom message

Dependents:   Robot_team1_QEI_Douglas Robot_team1

Revision:
0:020db18a476d
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros_lib/gazebo_msgs/ModelStates.h	Wed Oct 30 14:59:49 2019 +0000
@@ -0,0 +1,127 @@
+#ifndef _ROS_gazebo_msgs_ModelStates_h
+#define _ROS_gazebo_msgs_ModelStates_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Twist.h"
+
+namespace gazebo_msgs
+{
+
+  class ModelStates : public ros::Msg
+  {
+    public:
+      uint32_t name_length;
+      typedef char* _name_type;
+      _name_type st_name;
+      _name_type * name;
+      uint32_t pose_length;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type st_pose;
+      _pose_type * pose;
+      uint32_t twist_length;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type st_twist;
+      _twist_type * twist;
+
+    ModelStates():
+      name_length(0), name(NULL),
+      pose_length(0), pose(NULL),
+      twist_length(0), twist(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->name_length);
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      varToArr(outbuffer + offset, length_namei);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset + 0) = (this->pose_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->pose_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->pose_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->pose_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->pose_length);
+      for( uint32_t i = 0; i < pose_length; i++){
+      offset += this->pose[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->twist_length);
+      for( uint32_t i = 0; i < twist_length; i++){
+      offset += this->twist[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->name_length);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      name_length = name_lengthT;
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      arrToVar(length_st_name, (inbuffer + offset));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_name-1]=0;
+      this->st_name = (char *)(inbuffer + offset-1);
+      offset += length_st_name;
+        memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
+      }
+      uint32_t pose_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->pose_length);
+      if(pose_lengthT > pose_length)
+        this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
+      pose_length = pose_lengthT;
+      for( uint32_t i = 0; i < pose_length; i++){
+      offset += this->st_pose.deserialize(inbuffer + offset);
+        memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
+      }
+      uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->twist_length);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      twist_length = twist_lengthT;
+      for( uint32_t i = 0; i < twist_length; i++){
+      offset += this->st_twist.deserialize(inbuffer + offset);
+        memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/ModelStates"; };
+    const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; };
+
+  };
+
+}
+#endif