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/GetLinkProperties.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_GetLinkProperties_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_SERVICE_GetLinkProperties_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 | |
akashvibhute | 0:30537dec6e0b | 9 | namespace gazebo_msgs |
akashvibhute | 0:30537dec6e0b | 10 | { |
akashvibhute | 0:30537dec6e0b | 11 | |
akashvibhute | 0:30537dec6e0b | 12 | static const char GETLINKPROPERTIES[] = "gazebo_msgs/GetLinkProperties"; |
akashvibhute | 0:30537dec6e0b | 13 | |
akashvibhute | 0:30537dec6e0b | 14 | class GetLinkPropertiesRequest : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 15 | { |
akashvibhute | 0:30537dec6e0b | 16 | public: |
akashvibhute | 0:30537dec6e0b | 17 | const char* link_name; |
akashvibhute | 0:30537dec6e0b | 18 | |
akashvibhute | 0:30537dec6e0b | 19 | GetLinkPropertiesRequest(): |
akashvibhute | 0:30537dec6e0b | 20 | link_name("") |
akashvibhute | 0:30537dec6e0b | 21 | { |
akashvibhute | 0:30537dec6e0b | 22 | } |
akashvibhute | 0:30537dec6e0b | 23 | |
akashvibhute | 0:30537dec6e0b | 24 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 25 | { |
akashvibhute | 0:30537dec6e0b | 26 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 27 | uint32_t length_link_name = strlen(this->link_name); |
akashvibhute | 0:30537dec6e0b | 28 | memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 29 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 30 | memcpy(outbuffer + offset, this->link_name, length_link_name); |
akashvibhute | 0:30537dec6e0b | 31 | offset += length_link_name; |
akashvibhute | 0:30537dec6e0b | 32 | return offset; |
akashvibhute | 0:30537dec6e0b | 33 | } |
akashvibhute | 0:30537dec6e0b | 34 | |
akashvibhute | 0:30537dec6e0b | 35 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 36 | { |
akashvibhute | 0:30537dec6e0b | 37 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 38 | uint32_t length_link_name; |
akashvibhute | 0:30537dec6e0b | 39 | memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 40 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 41 | for(unsigned int k= offset; k< offset+length_link_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 42 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 43 | } |
akashvibhute | 0:30537dec6e0b | 44 | inbuffer[offset+length_link_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 45 | this->link_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 46 | offset += length_link_name; |
akashvibhute | 0:30537dec6e0b | 47 | return offset; |
akashvibhute | 0:30537dec6e0b | 48 | } |
akashvibhute | 0:30537dec6e0b | 49 | |
akashvibhute | 0:30537dec6e0b | 50 | const char * getType(){ return GETLINKPROPERTIES; }; |
akashvibhute | 0:30537dec6e0b | 51 | const char * getMD5(){ return "7d82d60381f1b66a30f2157f60884345"; }; |
akashvibhute | 0:30537dec6e0b | 52 | |
akashvibhute | 0:30537dec6e0b | 53 | }; |
akashvibhute | 0:30537dec6e0b | 54 | |
akashvibhute | 0:30537dec6e0b | 55 | class GetLinkPropertiesResponse : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 56 | { |
akashvibhute | 0:30537dec6e0b | 57 | public: |
akashvibhute | 0:30537dec6e0b | 58 | geometry_msgs::Pose com; |
akashvibhute | 0:30537dec6e0b | 59 | bool gravity_mode; |
akashvibhute | 0:30537dec6e0b | 60 | float mass; |
akashvibhute | 0:30537dec6e0b | 61 | float ixx; |
akashvibhute | 0:30537dec6e0b | 62 | float ixy; |
akashvibhute | 0:30537dec6e0b | 63 | float ixz; |
akashvibhute | 0:30537dec6e0b | 64 | float iyy; |
akashvibhute | 0:30537dec6e0b | 65 | float iyz; |
akashvibhute | 0:30537dec6e0b | 66 | float izz; |
akashvibhute | 0:30537dec6e0b | 67 | bool success; |
akashvibhute | 0:30537dec6e0b | 68 | const char* status_message; |
akashvibhute | 0:30537dec6e0b | 69 | |
akashvibhute | 0:30537dec6e0b | 70 | GetLinkPropertiesResponse(): |
akashvibhute | 0:30537dec6e0b | 71 | com(), |
akashvibhute | 0:30537dec6e0b | 72 | gravity_mode(0), |
akashvibhute | 0:30537dec6e0b | 73 | mass(0), |
akashvibhute | 0:30537dec6e0b | 74 | ixx(0), |
akashvibhute | 0:30537dec6e0b | 75 | ixy(0), |
akashvibhute | 0:30537dec6e0b | 76 | ixz(0), |
akashvibhute | 0:30537dec6e0b | 77 | iyy(0), |
akashvibhute | 0:30537dec6e0b | 78 | iyz(0), |
akashvibhute | 0:30537dec6e0b | 79 | izz(0), |
akashvibhute | 0:30537dec6e0b | 80 | success(0), |
akashvibhute | 0:30537dec6e0b | 81 | status_message("") |
akashvibhute | 0:30537dec6e0b | 82 | { |
akashvibhute | 0:30537dec6e0b | 83 | } |
akashvibhute | 0:30537dec6e0b | 84 | |
akashvibhute | 0:30537dec6e0b | 85 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 86 | { |
akashvibhute | 0:30537dec6e0b | 87 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 88 | offset += this->com.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 89 | union { |
akashvibhute | 0:30537dec6e0b | 90 | bool real; |
akashvibhute | 0:30537dec6e0b | 91 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 92 | } u_gravity_mode; |
akashvibhute | 0:30537dec6e0b | 93 | u_gravity_mode.real = this->gravity_mode; |
akashvibhute | 0:30537dec6e0b | 94 | *(outbuffer + offset + 0) = (u_gravity_mode.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 95 | offset += sizeof(this->gravity_mode); |
akashvibhute | 0:30537dec6e0b | 96 | offset += serializeAvrFloat64(outbuffer + offset, this->mass); |
akashvibhute | 0:30537dec6e0b | 97 | offset += serializeAvrFloat64(outbuffer + offset, this->ixx); |
akashvibhute | 0:30537dec6e0b | 98 | offset += serializeAvrFloat64(outbuffer + offset, this->ixy); |
akashvibhute | 0:30537dec6e0b | 99 | offset += serializeAvrFloat64(outbuffer + offset, this->ixz); |
akashvibhute | 0:30537dec6e0b | 100 | offset += serializeAvrFloat64(outbuffer + offset, this->iyy); |
akashvibhute | 0:30537dec6e0b | 101 | offset += serializeAvrFloat64(outbuffer + offset, this->iyz); |
akashvibhute | 0:30537dec6e0b | 102 | offset += serializeAvrFloat64(outbuffer + offset, this->izz); |
akashvibhute | 0:30537dec6e0b | 103 | union { |
akashvibhute | 0:30537dec6e0b | 104 | bool real; |
akashvibhute | 0:30537dec6e0b | 105 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 106 | } u_success; |
akashvibhute | 0:30537dec6e0b | 107 | u_success.real = this->success; |
akashvibhute | 0:30537dec6e0b | 108 | *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 109 | offset += sizeof(this->success); |
akashvibhute | 0:30537dec6e0b | 110 | uint32_t length_status_message = strlen(this->status_message); |
akashvibhute | 0:30537dec6e0b | 111 | memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 112 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 113 | memcpy(outbuffer + offset, this->status_message, length_status_message); |
akashvibhute | 0:30537dec6e0b | 114 | offset += length_status_message; |
akashvibhute | 0:30537dec6e0b | 115 | return offset; |
akashvibhute | 0:30537dec6e0b | 116 | } |
akashvibhute | 0:30537dec6e0b | 117 | |
akashvibhute | 0:30537dec6e0b | 118 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 119 | { |
akashvibhute | 0:30537dec6e0b | 120 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 121 | offset += this->com.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 122 | union { |
akashvibhute | 0:30537dec6e0b | 123 | bool real; |
akashvibhute | 0:30537dec6e0b | 124 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 125 | } u_gravity_mode; |
akashvibhute | 0:30537dec6e0b | 126 | u_gravity_mode.base = 0; |
akashvibhute | 0:30537dec6e0b | 127 | u_gravity_mode.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 128 | this->gravity_mode = u_gravity_mode.real; |
akashvibhute | 0:30537dec6e0b | 129 | offset += sizeof(this->gravity_mode); |
akashvibhute | 0:30537dec6e0b | 130 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->mass)); |
akashvibhute | 0:30537dec6e0b | 131 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixx)); |
akashvibhute | 0:30537dec6e0b | 132 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixy)); |
akashvibhute | 0:30537dec6e0b | 133 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixz)); |
akashvibhute | 0:30537dec6e0b | 134 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->iyy)); |
akashvibhute | 0:30537dec6e0b | 135 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->iyz)); |
akashvibhute | 0:30537dec6e0b | 136 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->izz)); |
akashvibhute | 0:30537dec6e0b | 137 | union { |
akashvibhute | 0:30537dec6e0b | 138 | bool real; |
akashvibhute | 0:30537dec6e0b | 139 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 140 | } u_success; |
akashvibhute | 0:30537dec6e0b | 141 | u_success.base = 0; |
akashvibhute | 0:30537dec6e0b | 142 | u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 143 | this->success = u_success.real; |
akashvibhute | 0:30537dec6e0b | 144 | offset += sizeof(this->success); |
akashvibhute | 0:30537dec6e0b | 145 | uint32_t length_status_message; |
akashvibhute | 0:30537dec6e0b | 146 | memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 147 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 148 | for(unsigned int k= offset; k< offset+length_status_message; ++k){ |
akashvibhute | 0:30537dec6e0b | 149 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 150 | } |
akashvibhute | 0:30537dec6e0b | 151 | inbuffer[offset+length_status_message-1]=0; |
akashvibhute | 0:30537dec6e0b | 152 | this->status_message = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 153 | offset += length_status_message; |
akashvibhute | 0:30537dec6e0b | 154 | return offset; |
akashvibhute | 0:30537dec6e0b | 155 | } |
akashvibhute | 0:30537dec6e0b | 156 | |
akashvibhute | 0:30537dec6e0b | 157 | const char * getType(){ return GETLINKPROPERTIES; }; |
akashvibhute | 0:30537dec6e0b | 158 | const char * getMD5(){ return "a8619f92d17cfcc3958c0fd13299443d"; }; |
akashvibhute | 0:30537dec6e0b | 159 | |
akashvibhute | 0:30537dec6e0b | 160 | }; |
akashvibhute | 0:30537dec6e0b | 161 | |
akashvibhute | 0:30537dec6e0b | 162 | class GetLinkProperties { |
akashvibhute | 0:30537dec6e0b | 163 | public: |
akashvibhute | 0:30537dec6e0b | 164 | typedef GetLinkPropertiesRequest Request; |
akashvibhute | 0:30537dec6e0b | 165 | typedef GetLinkPropertiesResponse Response; |
akashvibhute | 0:30537dec6e0b | 166 | }; |
akashvibhute | 0:30537dec6e0b | 167 | |
akashvibhute | 0:30537dec6e0b | 168 | } |
akashvibhute | 0:30537dec6e0b | 169 | #endif |
akashvibhute | 0:30537dec6e0b | 170 |