make changes on buffer serial

Dependencies:   BufferedSerial

Dependents:  

Committer:
Gary Servin
Date:
Fri Nov 08 14:38:09 2019 -0300
Revision:
0:04ac6be8229a
Initial commit, generated based on a clean melodic-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_gazebo_msgs_ModelState_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_gazebo_msgs_ModelState_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "geometry_msgs/Pose.h"
Gary Servin 0:04ac6be8229a 9 #include "geometry_msgs/Twist.h"
Gary Servin 0:04ac6be8229a 10
Gary Servin 0:04ac6be8229a 11 namespace gazebo_msgs
Gary Servin 0:04ac6be8229a 12 {
Gary Servin 0:04ac6be8229a 13
Gary Servin 0:04ac6be8229a 14 class ModelState : public ros::Msg
Gary Servin 0:04ac6be8229a 15 {
Gary Servin 0:04ac6be8229a 16 public:
Gary Servin 0:04ac6be8229a 17 typedef const char* _model_name_type;
Gary Servin 0:04ac6be8229a 18 _model_name_type model_name;
Gary Servin 0:04ac6be8229a 19 typedef geometry_msgs::Pose _pose_type;
Gary Servin 0:04ac6be8229a 20 _pose_type pose;
Gary Servin 0:04ac6be8229a 21 typedef geometry_msgs::Twist _twist_type;
Gary Servin 0:04ac6be8229a 22 _twist_type twist;
Gary Servin 0:04ac6be8229a 23 typedef const char* _reference_frame_type;
Gary Servin 0:04ac6be8229a 24 _reference_frame_type reference_frame;
Gary Servin 0:04ac6be8229a 25
Gary Servin 0:04ac6be8229a 26 ModelState():
Gary Servin 0:04ac6be8229a 27 model_name(""),
Gary Servin 0:04ac6be8229a 28 pose(),
Gary Servin 0:04ac6be8229a 29 twist(),
Gary Servin 0:04ac6be8229a 30 reference_frame("")
Gary Servin 0:04ac6be8229a 31 {
Gary Servin 0:04ac6be8229a 32 }
Gary Servin 0:04ac6be8229a 33
Gary Servin 0:04ac6be8229a 34 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 35 {
Gary Servin 0:04ac6be8229a 36 int offset = 0;
Gary Servin 0:04ac6be8229a 37 uint32_t length_model_name = strlen(this->model_name);
Gary Servin 0:04ac6be8229a 38 varToArr(outbuffer + offset, length_model_name);
Gary Servin 0:04ac6be8229a 39 offset += 4;
Gary Servin 0:04ac6be8229a 40 memcpy(outbuffer + offset, this->model_name, length_model_name);
Gary Servin 0:04ac6be8229a 41 offset += length_model_name;
Gary Servin 0:04ac6be8229a 42 offset += this->pose.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 43 offset += this->twist.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 44 uint32_t length_reference_frame = strlen(this->reference_frame);
Gary Servin 0:04ac6be8229a 45 varToArr(outbuffer + offset, length_reference_frame);
Gary Servin 0:04ac6be8229a 46 offset += 4;
Gary Servin 0:04ac6be8229a 47 memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
Gary Servin 0:04ac6be8229a 48 offset += length_reference_frame;
Gary Servin 0:04ac6be8229a 49 return offset;
Gary Servin 0:04ac6be8229a 50 }
Gary Servin 0:04ac6be8229a 51
Gary Servin 0:04ac6be8229a 52 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 53 {
Gary Servin 0:04ac6be8229a 54 int offset = 0;
Gary Servin 0:04ac6be8229a 55 uint32_t length_model_name;
Gary Servin 0:04ac6be8229a 56 arrToVar(length_model_name, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 57 offset += 4;
Gary Servin 0:04ac6be8229a 58 for(unsigned int k= offset; k< offset+length_model_name; ++k){
Gary Servin 0:04ac6be8229a 59 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 60 }
Gary Servin 0:04ac6be8229a 61 inbuffer[offset+length_model_name-1]=0;
Gary Servin 0:04ac6be8229a 62 this->model_name = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 63 offset += length_model_name;
Gary Servin 0:04ac6be8229a 64 offset += this->pose.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 65 offset += this->twist.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 66 uint32_t length_reference_frame;
Gary Servin 0:04ac6be8229a 67 arrToVar(length_reference_frame, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 68 offset += 4;
Gary Servin 0:04ac6be8229a 69 for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
Gary Servin 0:04ac6be8229a 70 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 71 }
Gary Servin 0:04ac6be8229a 72 inbuffer[offset+length_reference_frame-1]=0;
Gary Servin 0:04ac6be8229a 73 this->reference_frame = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 74 offset += length_reference_frame;
Gary Servin 0:04ac6be8229a 75 return offset;
Gary Servin 0:04ac6be8229a 76 }
Gary Servin 0:04ac6be8229a 77
Gary Servin 0:04ac6be8229a 78 const char * getType(){ return "gazebo_msgs/ModelState"; };
Gary Servin 0:04ac6be8229a 79 const char * getMD5(){ return "9330fd35f2fcd82d457e54bd54e10593"; };
Gary Servin 0:04ac6be8229a 80
Gary Servin 0:04ac6be8229a 81 };
Gary Servin 0:04ac6be8229a 82
Gary Servin 0:04ac6be8229a 83 }
Gary Servin 0:04ac6be8229a 84 #endif