It has only one change from original one. I added robotfeedback message on it.
Dependents: RobotFeedback mobileRobotITU
Fork of ros_lib_indigo by
gazebo_msgs/GetModelState.h@4:80d9bee5079a, 2017-03-04 (annotated)
- Committer:
- randalthor
- Date:
- Sat Mar 04 14:07:56 2017 +0000
- Revision:
- 4:80d9bee5079a
- Parent:
- 0:fd24f7ca9688
fatih
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:fd24f7ca9688 | 1 | #ifndef _ROS_SERVICE_GetModelState_h |
garyservin | 0:fd24f7ca9688 | 2 | #define _ROS_SERVICE_GetModelState_h |
garyservin | 0:fd24f7ca9688 | 3 | #include <stdint.h> |
garyservin | 0:fd24f7ca9688 | 4 | #include <string.h> |
garyservin | 0:fd24f7ca9688 | 5 | #include <stdlib.h> |
garyservin | 0:fd24f7ca9688 | 6 | #include "ros/msg.h" |
garyservin | 0:fd24f7ca9688 | 7 | #include "geometry_msgs/Pose.h" |
garyservin | 0:fd24f7ca9688 | 8 | #include "geometry_msgs/Twist.h" |
garyservin | 0:fd24f7ca9688 | 9 | |
garyservin | 0:fd24f7ca9688 | 10 | namespace gazebo_msgs |
garyservin | 0:fd24f7ca9688 | 11 | { |
garyservin | 0:fd24f7ca9688 | 12 | |
garyservin | 0:fd24f7ca9688 | 13 | static const char GETMODELSTATE[] = "gazebo_msgs/GetModelState"; |
garyservin | 0:fd24f7ca9688 | 14 | |
garyservin | 0:fd24f7ca9688 | 15 | class GetModelStateRequest : public ros::Msg |
garyservin | 0:fd24f7ca9688 | 16 | { |
garyservin | 0:fd24f7ca9688 | 17 | public: |
garyservin | 0:fd24f7ca9688 | 18 | const char* model_name; |
garyservin | 0:fd24f7ca9688 | 19 | const char* relative_entity_name; |
garyservin | 0:fd24f7ca9688 | 20 | |
garyservin | 0:fd24f7ca9688 | 21 | GetModelStateRequest(): |
garyservin | 0:fd24f7ca9688 | 22 | model_name(""), |
garyservin | 0:fd24f7ca9688 | 23 | relative_entity_name("") |
garyservin | 0:fd24f7ca9688 | 24 | { |
garyservin | 0:fd24f7ca9688 | 25 | } |
garyservin | 0:fd24f7ca9688 | 26 | |
garyservin | 0:fd24f7ca9688 | 27 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:fd24f7ca9688 | 28 | { |
garyservin | 0:fd24f7ca9688 | 29 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 30 | uint32_t length_model_name = strlen(this->model_name); |
garyservin | 0:fd24f7ca9688 | 31 | memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); |
garyservin | 0:fd24f7ca9688 | 32 | offset += 4; |
garyservin | 0:fd24f7ca9688 | 33 | memcpy(outbuffer + offset, this->model_name, length_model_name); |
garyservin | 0:fd24f7ca9688 | 34 | offset += length_model_name; |
garyservin | 0:fd24f7ca9688 | 35 | uint32_t length_relative_entity_name = strlen(this->relative_entity_name); |
garyservin | 0:fd24f7ca9688 | 36 | memcpy(outbuffer + offset, &length_relative_entity_name, sizeof(uint32_t)); |
garyservin | 0:fd24f7ca9688 | 37 | offset += 4; |
garyservin | 0:fd24f7ca9688 | 38 | memcpy(outbuffer + offset, this->relative_entity_name, length_relative_entity_name); |
garyservin | 0:fd24f7ca9688 | 39 | offset += length_relative_entity_name; |
garyservin | 0:fd24f7ca9688 | 40 | return offset; |
garyservin | 0:fd24f7ca9688 | 41 | } |
garyservin | 0:fd24f7ca9688 | 42 | |
garyservin | 0:fd24f7ca9688 | 43 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:fd24f7ca9688 | 44 | { |
garyservin | 0:fd24f7ca9688 | 45 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 46 | uint32_t length_model_name; |
garyservin | 0:fd24f7ca9688 | 47 | memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:fd24f7ca9688 | 48 | offset += 4; |
garyservin | 0:fd24f7ca9688 | 49 | for(unsigned int k= offset; k< offset+length_model_name; ++k){ |
garyservin | 0:fd24f7ca9688 | 50 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:fd24f7ca9688 | 51 | } |
garyservin | 0:fd24f7ca9688 | 52 | inbuffer[offset+length_model_name-1]=0; |
garyservin | 0:fd24f7ca9688 | 53 | this->model_name = (char *)(inbuffer + offset-1); |
garyservin | 0:fd24f7ca9688 | 54 | offset += length_model_name; |
garyservin | 0:fd24f7ca9688 | 55 | uint32_t length_relative_entity_name; |
garyservin | 0:fd24f7ca9688 | 56 | memcpy(&length_relative_entity_name, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:fd24f7ca9688 | 57 | offset += 4; |
garyservin | 0:fd24f7ca9688 | 58 | for(unsigned int k= offset; k< offset+length_relative_entity_name; ++k){ |
garyservin | 0:fd24f7ca9688 | 59 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:fd24f7ca9688 | 60 | } |
garyservin | 0:fd24f7ca9688 | 61 | inbuffer[offset+length_relative_entity_name-1]=0; |
garyservin | 0:fd24f7ca9688 | 62 | this->relative_entity_name = (char *)(inbuffer + offset-1); |
garyservin | 0:fd24f7ca9688 | 63 | offset += length_relative_entity_name; |
garyservin | 0:fd24f7ca9688 | 64 | return offset; |
garyservin | 0:fd24f7ca9688 | 65 | } |
garyservin | 0:fd24f7ca9688 | 66 | |
garyservin | 0:fd24f7ca9688 | 67 | const char * getType(){ return GETMODELSTATE; }; |
garyservin | 0:fd24f7ca9688 | 68 | const char * getMD5(){ return "19d412713cefe4a67437e17a951e759e"; }; |
garyservin | 0:fd24f7ca9688 | 69 | |
garyservin | 0:fd24f7ca9688 | 70 | }; |
garyservin | 0:fd24f7ca9688 | 71 | |
garyservin | 0:fd24f7ca9688 | 72 | class GetModelStateResponse : public ros::Msg |
garyservin | 0:fd24f7ca9688 | 73 | { |
garyservin | 0:fd24f7ca9688 | 74 | public: |
garyservin | 0:fd24f7ca9688 | 75 | geometry_msgs::Pose pose; |
garyservin | 0:fd24f7ca9688 | 76 | geometry_msgs::Twist twist; |
garyservin | 0:fd24f7ca9688 | 77 | bool success; |
garyservin | 0:fd24f7ca9688 | 78 | const char* status_message; |
garyservin | 0:fd24f7ca9688 | 79 | |
garyservin | 0:fd24f7ca9688 | 80 | GetModelStateResponse(): |
garyservin | 0:fd24f7ca9688 | 81 | pose(), |
garyservin | 0:fd24f7ca9688 | 82 | twist(), |
garyservin | 0:fd24f7ca9688 | 83 | success(0), |
garyservin | 0:fd24f7ca9688 | 84 | status_message("") |
garyservin | 0:fd24f7ca9688 | 85 | { |
garyservin | 0:fd24f7ca9688 | 86 | } |
garyservin | 0:fd24f7ca9688 | 87 | |
garyservin | 0:fd24f7ca9688 | 88 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:fd24f7ca9688 | 89 | { |
garyservin | 0:fd24f7ca9688 | 90 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 91 | offset += this->pose.serialize(outbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 92 | offset += this->twist.serialize(outbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 93 | union { |
garyservin | 0:fd24f7ca9688 | 94 | bool real; |
garyservin | 0:fd24f7ca9688 | 95 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 96 | } u_success; |
garyservin | 0:fd24f7ca9688 | 97 | u_success.real = this->success; |
garyservin | 0:fd24f7ca9688 | 98 | *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 99 | offset += sizeof(this->success); |
garyservin | 0:fd24f7ca9688 | 100 | uint32_t length_status_message = strlen(this->status_message); |
garyservin | 0:fd24f7ca9688 | 101 | memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); |
garyservin | 0:fd24f7ca9688 | 102 | offset += 4; |
garyservin | 0:fd24f7ca9688 | 103 | memcpy(outbuffer + offset, this->status_message, length_status_message); |
garyservin | 0:fd24f7ca9688 | 104 | offset += length_status_message; |
garyservin | 0:fd24f7ca9688 | 105 | return offset; |
garyservin | 0:fd24f7ca9688 | 106 | } |
garyservin | 0:fd24f7ca9688 | 107 | |
garyservin | 0:fd24f7ca9688 | 108 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:fd24f7ca9688 | 109 | { |
garyservin | 0:fd24f7ca9688 | 110 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 111 | offset += this->pose.deserialize(inbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 112 | offset += this->twist.deserialize(inbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 113 | union { |
garyservin | 0:fd24f7ca9688 | 114 | bool real; |
garyservin | 0:fd24f7ca9688 | 115 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 116 | } u_success; |
garyservin | 0:fd24f7ca9688 | 117 | u_success.base = 0; |
garyservin | 0:fd24f7ca9688 | 118 | u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 119 | this->success = u_success.real; |
garyservin | 0:fd24f7ca9688 | 120 | offset += sizeof(this->success); |
garyservin | 0:fd24f7ca9688 | 121 | uint32_t length_status_message; |
garyservin | 0:fd24f7ca9688 | 122 | memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:fd24f7ca9688 | 123 | offset += 4; |
garyservin | 0:fd24f7ca9688 | 124 | for(unsigned int k= offset; k< offset+length_status_message; ++k){ |
garyservin | 0:fd24f7ca9688 | 125 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:fd24f7ca9688 | 126 | } |
garyservin | 0:fd24f7ca9688 | 127 | inbuffer[offset+length_status_message-1]=0; |
garyservin | 0:fd24f7ca9688 | 128 | this->status_message = (char *)(inbuffer + offset-1); |
garyservin | 0:fd24f7ca9688 | 129 | offset += length_status_message; |
garyservin | 0:fd24f7ca9688 | 130 | return offset; |
garyservin | 0:fd24f7ca9688 | 131 | } |
garyservin | 0:fd24f7ca9688 | 132 | |
garyservin | 0:fd24f7ca9688 | 133 | const char * getType(){ return GETMODELSTATE; }; |
garyservin | 0:fd24f7ca9688 | 134 | const char * getMD5(){ return "1f8f991dc94e0cb27fe61383e0f576bb"; }; |
garyservin | 0:fd24f7ca9688 | 135 | |
garyservin | 0:fd24f7ca9688 | 136 | }; |
garyservin | 0:fd24f7ca9688 | 137 | |
garyservin | 0:fd24f7ca9688 | 138 | class GetModelState { |
garyservin | 0:fd24f7ca9688 | 139 | public: |
garyservin | 0:fd24f7ca9688 | 140 | typedef GetModelStateRequest Request; |
garyservin | 0:fd24f7ca9688 | 141 | typedef GetModelStateResponse Response; |
garyservin | 0:fd24f7ca9688 | 142 | }; |
garyservin | 0:fd24f7ca9688 | 143 | |
garyservin | 0:fd24f7ca9688 | 144 | } |
garyservin | 0:fd24f7ca9688 | 145 | #endif |