hairo
Dependencies: mbed BufferedSerial
gazebo_msgs/ModelStates.h@0:9e9b7db60fd5, 2016-12-31 (annotated)
- Committer:
- garyservin
- Date:
- Sat Dec 31 00:48:34 2016 +0000
- Revision:
- 0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_gazebo_msgs_ModelStates_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_gazebo_msgs_ModelStates_h |
garyservin | 0:9e9b7db60fd5 | 3 | |
garyservin | 0:9e9b7db60fd5 | 4 | #include <stdint.h> |
garyservin | 0:9e9b7db60fd5 | 5 | #include <string.h> |
garyservin | 0:9e9b7db60fd5 | 6 | #include <stdlib.h> |
garyservin | 0:9e9b7db60fd5 | 7 | #include "ros/msg.h" |
garyservin | 0:9e9b7db60fd5 | 8 | #include "geometry_msgs/Pose.h" |
garyservin | 0:9e9b7db60fd5 | 9 | #include "geometry_msgs/Twist.h" |
garyservin | 0:9e9b7db60fd5 | 10 | |
garyservin | 0:9e9b7db60fd5 | 11 | namespace gazebo_msgs |
garyservin | 0:9e9b7db60fd5 | 12 | { |
garyservin | 0:9e9b7db60fd5 | 13 | |
garyservin | 0:9e9b7db60fd5 | 14 | class ModelStates : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 15 | { |
garyservin | 0:9e9b7db60fd5 | 16 | public: |
garyservin | 0:9e9b7db60fd5 | 17 | uint32_t name_length; |
garyservin | 0:9e9b7db60fd5 | 18 | typedef char* _name_type; |
garyservin | 0:9e9b7db60fd5 | 19 | _name_type st_name; |
garyservin | 0:9e9b7db60fd5 | 20 | _name_type * name; |
garyservin | 0:9e9b7db60fd5 | 21 | uint32_t pose_length; |
garyservin | 0:9e9b7db60fd5 | 22 | typedef geometry_msgs::Pose _pose_type; |
garyservin | 0:9e9b7db60fd5 | 23 | _pose_type st_pose; |
garyservin | 0:9e9b7db60fd5 | 24 | _pose_type * pose; |
garyservin | 0:9e9b7db60fd5 | 25 | uint32_t twist_length; |
garyservin | 0:9e9b7db60fd5 | 26 | typedef geometry_msgs::Twist _twist_type; |
garyservin | 0:9e9b7db60fd5 | 27 | _twist_type st_twist; |
garyservin | 0:9e9b7db60fd5 | 28 | _twist_type * twist; |
garyservin | 0:9e9b7db60fd5 | 29 | |
garyservin | 0:9e9b7db60fd5 | 30 | ModelStates(): |
garyservin | 0:9e9b7db60fd5 | 31 | name_length(0), name(NULL), |
garyservin | 0:9e9b7db60fd5 | 32 | pose_length(0), pose(NULL), |
garyservin | 0:9e9b7db60fd5 | 33 | twist_length(0), twist(NULL) |
garyservin | 0:9e9b7db60fd5 | 34 | { |
garyservin | 0:9e9b7db60fd5 | 35 | } |
garyservin | 0:9e9b7db60fd5 | 36 | |
garyservin | 0:9e9b7db60fd5 | 37 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 38 | { |
garyservin | 0:9e9b7db60fd5 | 39 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 40 | *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 41 | *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 42 | *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 43 | *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 44 | offset += sizeof(this->name_length); |
garyservin | 0:9e9b7db60fd5 | 45 | for( uint32_t i = 0; i < name_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 46 | uint32_t length_namei = strlen(this->name[i]); |
garyservin | 0:9e9b7db60fd5 | 47 | varToArr(outbuffer + offset, length_namei); |
garyservin | 0:9e9b7db60fd5 | 48 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 49 | memcpy(outbuffer + offset, this->name[i], length_namei); |
garyservin | 0:9e9b7db60fd5 | 50 | offset += length_namei; |
garyservin | 0:9e9b7db60fd5 | 51 | } |
garyservin | 0:9e9b7db60fd5 | 52 | *(outbuffer + offset + 0) = (this->pose_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 53 | *(outbuffer + offset + 1) = (this->pose_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 54 | *(outbuffer + offset + 2) = (this->pose_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 55 | *(outbuffer + offset + 3) = (this->pose_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 56 | offset += sizeof(this->pose_length); |
garyservin | 0:9e9b7db60fd5 | 57 | for( uint32_t i = 0; i < pose_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 58 | offset += this->pose[i].serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 59 | } |
garyservin | 0:9e9b7db60fd5 | 60 | *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 61 | *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 62 | *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 63 | *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 64 | offset += sizeof(this->twist_length); |
garyservin | 0:9e9b7db60fd5 | 65 | for( uint32_t i = 0; i < twist_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 66 | offset += this->twist[i].serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 67 | } |
garyservin | 0:9e9b7db60fd5 | 68 | return offset; |
garyservin | 0:9e9b7db60fd5 | 69 | } |
garyservin | 0:9e9b7db60fd5 | 70 | |
garyservin | 0:9e9b7db60fd5 | 71 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 72 | { |
garyservin | 0:9e9b7db60fd5 | 73 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 74 | uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 75 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 76 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 77 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 78 | offset += sizeof(this->name_length); |
garyservin | 0:9e9b7db60fd5 | 79 | if(name_lengthT > name_length) |
garyservin | 0:9e9b7db60fd5 | 80 | this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 81 | name_length = name_lengthT; |
garyservin | 0:9e9b7db60fd5 | 82 | for( uint32_t i = 0; i < name_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 83 | uint32_t length_st_name; |
garyservin | 0:9e9b7db60fd5 | 84 | arrToVar(length_st_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 85 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 86 | for(unsigned int k= offset; k< offset+length_st_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 87 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 88 | } |
garyservin | 0:9e9b7db60fd5 | 89 | inbuffer[offset+length_st_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 90 | this->st_name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 91 | offset += length_st_name; |
garyservin | 0:9e9b7db60fd5 | 92 | memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 93 | } |
garyservin | 0:9e9b7db60fd5 | 94 | uint32_t pose_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 95 | pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 96 | pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 97 | pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 98 | offset += sizeof(this->pose_length); |
garyservin | 0:9e9b7db60fd5 | 99 | if(pose_lengthT > pose_length) |
garyservin | 0:9e9b7db60fd5 | 100 | this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose)); |
garyservin | 0:9e9b7db60fd5 | 101 | pose_length = pose_lengthT; |
garyservin | 0:9e9b7db60fd5 | 102 | for( uint32_t i = 0; i < pose_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 103 | offset += this->st_pose.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 104 | memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose)); |
garyservin | 0:9e9b7db60fd5 | 105 | } |
garyservin | 0:9e9b7db60fd5 | 106 | uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 107 | twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 108 | twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 109 | twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 110 | offset += sizeof(this->twist_length); |
garyservin | 0:9e9b7db60fd5 | 111 | if(twist_lengthT > twist_length) |
garyservin | 0:9e9b7db60fd5 | 112 | this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); |
garyservin | 0:9e9b7db60fd5 | 113 | twist_length = twist_lengthT; |
garyservin | 0:9e9b7db60fd5 | 114 | for( uint32_t i = 0; i < twist_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 115 | offset += this->st_twist.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 116 | memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); |
garyservin | 0:9e9b7db60fd5 | 117 | } |
garyservin | 0:9e9b7db60fd5 | 118 | return offset; |
garyservin | 0:9e9b7db60fd5 | 119 | } |
garyservin | 0:9e9b7db60fd5 | 120 | |
garyservin | 0:9e9b7db60fd5 | 121 | const char * getType(){ return "gazebo_msgs/ModelStates"; }; |
garyservin | 0:9e9b7db60fd5 | 122 | const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; }; |
garyservin | 0:9e9b7db60fd5 | 123 | |
garyservin | 0:9e9b7db60fd5 | 124 | }; |
garyservin | 0:9e9b7db60fd5 | 125 | |
garyservin | 0:9e9b7db60fd5 | 126 | } |
garyservin | 0:9e9b7db60fd5 | 127 | #endif |