rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
gazebo_msgs/GetModelState.h@0:30537dec6e0b, 2015-02-15 (annotated)
- Committer:
- akashvibhute
- Date:
- Sun Feb 15 10:53:43 2015 +0000
- Revision:
- 0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
akashvibhute | 0:30537dec6e0b | 1 | #ifndef _ROS_SERVICE_GetModelState_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_SERVICE_GetModelState_h |
akashvibhute | 0:30537dec6e0b | 3 | #include <stdint.h> |
akashvibhute | 0:30537dec6e0b | 4 | #include <string.h> |
akashvibhute | 0:30537dec6e0b | 5 | #include <stdlib.h> |
akashvibhute | 0:30537dec6e0b | 6 | #include "ros/msg.h" |
akashvibhute | 0:30537dec6e0b | 7 | #include "geometry_msgs/Pose.h" |
akashvibhute | 0:30537dec6e0b | 8 | #include "geometry_msgs/Twist.h" |
akashvibhute | 0:30537dec6e0b | 9 | |
akashvibhute | 0:30537dec6e0b | 10 | namespace gazebo_msgs |
akashvibhute | 0:30537dec6e0b | 11 | { |
akashvibhute | 0:30537dec6e0b | 12 | |
akashvibhute | 0:30537dec6e0b | 13 | static const char GETMODELSTATE[] = "gazebo_msgs/GetModelState"; |
akashvibhute | 0:30537dec6e0b | 14 | |
akashvibhute | 0:30537dec6e0b | 15 | class GetModelStateRequest : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 16 | { |
akashvibhute | 0:30537dec6e0b | 17 | public: |
akashvibhute | 0:30537dec6e0b | 18 | const char* model_name; |
akashvibhute | 0:30537dec6e0b | 19 | const char* relative_entity_name; |
akashvibhute | 0:30537dec6e0b | 20 | |
akashvibhute | 0:30537dec6e0b | 21 | GetModelStateRequest(): |
akashvibhute | 0:30537dec6e0b | 22 | model_name(""), |
akashvibhute | 0:30537dec6e0b | 23 | relative_entity_name("") |
akashvibhute | 0:30537dec6e0b | 24 | { |
akashvibhute | 0:30537dec6e0b | 25 | } |
akashvibhute | 0:30537dec6e0b | 26 | |
akashvibhute | 0:30537dec6e0b | 27 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 28 | { |
akashvibhute | 0:30537dec6e0b | 29 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 30 | uint32_t length_model_name = strlen(this->model_name); |
akashvibhute | 0:30537dec6e0b | 31 | memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 32 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 33 | memcpy(outbuffer + offset, this->model_name, length_model_name); |
akashvibhute | 0:30537dec6e0b | 34 | offset += length_model_name; |
akashvibhute | 0:30537dec6e0b | 35 | uint32_t length_relative_entity_name = strlen(this->relative_entity_name); |
akashvibhute | 0:30537dec6e0b | 36 | memcpy(outbuffer + offset, &length_relative_entity_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 37 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 38 | memcpy(outbuffer + offset, this->relative_entity_name, length_relative_entity_name); |
akashvibhute | 0:30537dec6e0b | 39 | offset += length_relative_entity_name; |
akashvibhute | 0:30537dec6e0b | 40 | return offset; |
akashvibhute | 0:30537dec6e0b | 41 | } |
akashvibhute | 0:30537dec6e0b | 42 | |
akashvibhute | 0:30537dec6e0b | 43 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 44 | { |
akashvibhute | 0:30537dec6e0b | 45 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 46 | uint32_t length_model_name; |
akashvibhute | 0:30537dec6e0b | 47 | memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 48 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 49 | for(unsigned int k= offset; k< offset+length_model_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 50 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 51 | } |
akashvibhute | 0:30537dec6e0b | 52 | inbuffer[offset+length_model_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 53 | this->model_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 54 | offset += length_model_name; |
akashvibhute | 0:30537dec6e0b | 55 | uint32_t length_relative_entity_name; |
akashvibhute | 0:30537dec6e0b | 56 | memcpy(&length_relative_entity_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 57 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 58 | for(unsigned int k= offset; k< offset+length_relative_entity_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 59 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 60 | } |
akashvibhute | 0:30537dec6e0b | 61 | inbuffer[offset+length_relative_entity_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 62 | this->relative_entity_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 63 | offset += length_relative_entity_name; |
akashvibhute | 0:30537dec6e0b | 64 | return offset; |
akashvibhute | 0:30537dec6e0b | 65 | } |
akashvibhute | 0:30537dec6e0b | 66 | |
akashvibhute | 0:30537dec6e0b | 67 | const char * getType(){ return GETMODELSTATE; }; |
akashvibhute | 0:30537dec6e0b | 68 | const char * getMD5(){ return "19d412713cefe4a67437e17a951e759e"; }; |
akashvibhute | 0:30537dec6e0b | 69 | |
akashvibhute | 0:30537dec6e0b | 70 | }; |
akashvibhute | 0:30537dec6e0b | 71 | |
akashvibhute | 0:30537dec6e0b | 72 | class GetModelStateResponse : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 73 | { |
akashvibhute | 0:30537dec6e0b | 74 | public: |
akashvibhute | 0:30537dec6e0b | 75 | geometry_msgs::Pose pose; |
akashvibhute | 0:30537dec6e0b | 76 | geometry_msgs::Twist twist; |
akashvibhute | 0:30537dec6e0b | 77 | bool success; |
akashvibhute | 0:30537dec6e0b | 78 | const char* status_message; |
akashvibhute | 0:30537dec6e0b | 79 | |
akashvibhute | 0:30537dec6e0b | 80 | GetModelStateResponse(): |
akashvibhute | 0:30537dec6e0b | 81 | pose(), |
akashvibhute | 0:30537dec6e0b | 82 | twist(), |
akashvibhute | 0:30537dec6e0b | 83 | success(0), |
akashvibhute | 0:30537dec6e0b | 84 | status_message("") |
akashvibhute | 0:30537dec6e0b | 85 | { |
akashvibhute | 0:30537dec6e0b | 86 | } |
akashvibhute | 0:30537dec6e0b | 87 | |
akashvibhute | 0:30537dec6e0b | 88 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 89 | { |
akashvibhute | 0:30537dec6e0b | 90 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 91 | offset += this->pose.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 92 | offset += this->twist.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 93 | union { |
akashvibhute | 0:30537dec6e0b | 94 | bool real; |
akashvibhute | 0:30537dec6e0b | 95 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 96 | } u_success; |
akashvibhute | 0:30537dec6e0b | 97 | u_success.real = this->success; |
akashvibhute | 0:30537dec6e0b | 98 | *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 99 | offset += sizeof(this->success); |
akashvibhute | 0:30537dec6e0b | 100 | uint32_t length_status_message = strlen(this->status_message); |
akashvibhute | 0:30537dec6e0b | 101 | memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 102 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 103 | memcpy(outbuffer + offset, this->status_message, length_status_message); |
akashvibhute | 0:30537dec6e0b | 104 | offset += length_status_message; |
akashvibhute | 0:30537dec6e0b | 105 | return offset; |
akashvibhute | 0:30537dec6e0b | 106 | } |
akashvibhute | 0:30537dec6e0b | 107 | |
akashvibhute | 0:30537dec6e0b | 108 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 109 | { |
akashvibhute | 0:30537dec6e0b | 110 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 111 | offset += this->pose.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 112 | offset += this->twist.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 113 | union { |
akashvibhute | 0:30537dec6e0b | 114 | bool real; |
akashvibhute | 0:30537dec6e0b | 115 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 116 | } u_success; |
akashvibhute | 0:30537dec6e0b | 117 | u_success.base = 0; |
akashvibhute | 0:30537dec6e0b | 118 | u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 119 | this->success = u_success.real; |
akashvibhute | 0:30537dec6e0b | 120 | offset += sizeof(this->success); |
akashvibhute | 0:30537dec6e0b | 121 | uint32_t length_status_message; |
akashvibhute | 0:30537dec6e0b | 122 | memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 123 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 124 | for(unsigned int k= offset; k< offset+length_status_message; ++k){ |
akashvibhute | 0:30537dec6e0b | 125 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 126 | } |
akashvibhute | 0:30537dec6e0b | 127 | inbuffer[offset+length_status_message-1]=0; |
akashvibhute | 0:30537dec6e0b | 128 | this->status_message = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 129 | offset += length_status_message; |
akashvibhute | 0:30537dec6e0b | 130 | return offset; |
akashvibhute | 0:30537dec6e0b | 131 | } |
akashvibhute | 0:30537dec6e0b | 132 | |
akashvibhute | 0:30537dec6e0b | 133 | const char * getType(){ return GETMODELSTATE; }; |
akashvibhute | 0:30537dec6e0b | 134 | const char * getMD5(){ return "1f8f991dc94e0cb27fe61383e0f576bb"; }; |
akashvibhute | 0:30537dec6e0b | 135 | |
akashvibhute | 0:30537dec6e0b | 136 | }; |
akashvibhute | 0:30537dec6e0b | 137 | |
akashvibhute | 0:30537dec6e0b | 138 | class GetModelState { |
akashvibhute | 0:30537dec6e0b | 139 | public: |
akashvibhute | 0:30537dec6e0b | 140 | typedef GetModelStateRequest Request; |
akashvibhute | 0:30537dec6e0b | 141 | typedef GetModelStateResponse Response; |
akashvibhute | 0:30537dec6e0b | 142 | }; |
akashvibhute | 0:30537dec6e0b | 143 | |
akashvibhute | 0:30537dec6e0b | 144 | } |
akashvibhute | 0:30537dec6e0b | 145 | #endif |
akashvibhute | 0:30537dec6e0b | 146 |