ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.
gazebo_msgs/GetLinkState.h@0:04ac6be8229a, 2019-11-08 (annotated)
- 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?
User | Revision | Line number | New contents of line |
---|---|---|---|
Gary Servin |
0:04ac6be8229a | 1 | #ifndef _ROS_SERVICE_GetLinkState_h |
Gary Servin |
0:04ac6be8229a | 2 | #define _ROS_SERVICE_GetLinkState_h |
Gary Servin |
0:04ac6be8229a | 3 | #include <stdint.h> |
Gary Servin |
0:04ac6be8229a | 4 | #include <string.h> |
Gary Servin |
0:04ac6be8229a | 5 | #include <stdlib.h> |
Gary Servin |
0:04ac6be8229a | 6 | #include "ros/msg.h" |
Gary Servin |
0:04ac6be8229a | 7 | #include "gazebo_msgs/LinkState.h" |
Gary Servin |
0:04ac6be8229a | 8 | |
Gary Servin |
0:04ac6be8229a | 9 | namespace gazebo_msgs |
Gary Servin |
0:04ac6be8229a | 10 | { |
Gary Servin |
0:04ac6be8229a | 11 | |
Gary Servin |
0:04ac6be8229a | 12 | static const char GETLINKSTATE[] = "gazebo_msgs/GetLinkState"; |
Gary Servin |
0:04ac6be8229a | 13 | |
Gary Servin |
0:04ac6be8229a | 14 | class GetLinkStateRequest : public ros::Msg |
Gary Servin |
0:04ac6be8229a | 15 | { |
Gary Servin |
0:04ac6be8229a | 16 | public: |
Gary Servin |
0:04ac6be8229a | 17 | typedef const char* _link_name_type; |
Gary Servin |
0:04ac6be8229a | 18 | _link_name_type link_name; |
Gary Servin |
0:04ac6be8229a | 19 | typedef const char* _reference_frame_type; |
Gary Servin |
0:04ac6be8229a | 20 | _reference_frame_type reference_frame; |
Gary Servin |
0:04ac6be8229a | 21 | |
Gary Servin |
0:04ac6be8229a | 22 | GetLinkStateRequest(): |
Gary Servin |
0:04ac6be8229a | 23 | link_name(""), |
Gary Servin |
0:04ac6be8229a | 24 | reference_frame("") |
Gary Servin |
0:04ac6be8229a | 25 | { |
Gary Servin |
0:04ac6be8229a | 26 | } |
Gary Servin |
0:04ac6be8229a | 27 | |
Gary Servin |
0:04ac6be8229a | 28 | virtual int serialize(unsigned char *outbuffer) const |
Gary Servin |
0:04ac6be8229a | 29 | { |
Gary Servin |
0:04ac6be8229a | 30 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 31 | uint32_t length_link_name = strlen(this->link_name); |
Gary Servin |
0:04ac6be8229a | 32 | varToArr(outbuffer + offset, length_link_name); |
Gary Servin |
0:04ac6be8229a | 33 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 34 | memcpy(outbuffer + offset, this->link_name, length_link_name); |
Gary Servin |
0:04ac6be8229a | 35 | offset += length_link_name; |
Gary Servin |
0:04ac6be8229a | 36 | uint32_t length_reference_frame = strlen(this->reference_frame); |
Gary Servin |
0:04ac6be8229a | 37 | varToArr(outbuffer + offset, length_reference_frame); |
Gary Servin |
0:04ac6be8229a | 38 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 39 | memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); |
Gary Servin |
0:04ac6be8229a | 40 | offset += length_reference_frame; |
Gary Servin |
0:04ac6be8229a | 41 | return offset; |
Gary Servin |
0:04ac6be8229a | 42 | } |
Gary Servin |
0:04ac6be8229a | 43 | |
Gary Servin |
0:04ac6be8229a | 44 | virtual int deserialize(unsigned char *inbuffer) |
Gary Servin |
0:04ac6be8229a | 45 | { |
Gary Servin |
0:04ac6be8229a | 46 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 47 | uint32_t length_link_name; |
Gary Servin |
0:04ac6be8229a | 48 | arrToVar(length_link_name, (inbuffer + offset)); |
Gary Servin |
0:04ac6be8229a | 49 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 50 | for(unsigned int k= offset; k< offset+length_link_name; ++k){ |
Gary Servin |
0:04ac6be8229a | 51 | inbuffer[k-1]=inbuffer[k]; |
Gary Servin |
0:04ac6be8229a | 52 | } |
Gary Servin |
0:04ac6be8229a | 53 | inbuffer[offset+length_link_name-1]=0; |
Gary Servin |
0:04ac6be8229a | 54 | this->link_name = (char *)(inbuffer + offset-1); |
Gary Servin |
0:04ac6be8229a | 55 | offset += length_link_name; |
Gary Servin |
0:04ac6be8229a | 56 | uint32_t length_reference_frame; |
Gary Servin |
0:04ac6be8229a | 57 | arrToVar(length_reference_frame, (inbuffer + offset)); |
Gary Servin |
0:04ac6be8229a | 58 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 59 | for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ |
Gary Servin |
0:04ac6be8229a | 60 | inbuffer[k-1]=inbuffer[k]; |
Gary Servin |
0:04ac6be8229a | 61 | } |
Gary Servin |
0:04ac6be8229a | 62 | inbuffer[offset+length_reference_frame-1]=0; |
Gary Servin |
0:04ac6be8229a | 63 | this->reference_frame = (char *)(inbuffer + offset-1); |
Gary Servin |
0:04ac6be8229a | 64 | offset += length_reference_frame; |
Gary Servin |
0:04ac6be8229a | 65 | return offset; |
Gary Servin |
0:04ac6be8229a | 66 | } |
Gary Servin |
0:04ac6be8229a | 67 | |
Gary Servin |
0:04ac6be8229a | 68 | const char * getType(){ return GETLINKSTATE; }; |
Gary Servin |
0:04ac6be8229a | 69 | const char * getMD5(){ return "7551675c30aaa71f7c288d4864552001"; }; |
Gary Servin |
0:04ac6be8229a | 70 | |
Gary Servin |
0:04ac6be8229a | 71 | }; |
Gary Servin |
0:04ac6be8229a | 72 | |
Gary Servin |
0:04ac6be8229a | 73 | class GetLinkStateResponse : public ros::Msg |
Gary Servin |
0:04ac6be8229a | 74 | { |
Gary Servin |
0:04ac6be8229a | 75 | public: |
Gary Servin |
0:04ac6be8229a | 76 | typedef gazebo_msgs::LinkState _link_state_type; |
Gary Servin |
0:04ac6be8229a | 77 | _link_state_type link_state; |
Gary Servin |
0:04ac6be8229a | 78 | typedef bool _success_type; |
Gary Servin |
0:04ac6be8229a | 79 | _success_type success; |
Gary Servin |
0:04ac6be8229a | 80 | typedef const char* _status_message_type; |
Gary Servin |
0:04ac6be8229a | 81 | _status_message_type status_message; |
Gary Servin |
0:04ac6be8229a | 82 | |
Gary Servin |
0:04ac6be8229a | 83 | GetLinkStateResponse(): |
Gary Servin |
0:04ac6be8229a | 84 | link_state(), |
Gary Servin |
0:04ac6be8229a | 85 | success(0), |
Gary Servin |
0:04ac6be8229a | 86 | status_message("") |
Gary Servin |
0:04ac6be8229a | 87 | { |
Gary Servin |
0:04ac6be8229a | 88 | } |
Gary Servin |
0:04ac6be8229a | 89 | |
Gary Servin |
0:04ac6be8229a | 90 | virtual int serialize(unsigned char *outbuffer) const |
Gary Servin |
0:04ac6be8229a | 91 | { |
Gary Servin |
0:04ac6be8229a | 92 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 93 | offset += this->link_state.serialize(outbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 94 | union { |
Gary Servin |
0:04ac6be8229a | 95 | bool real; |
Gary Servin |
0:04ac6be8229a | 96 | uint8_t base; |
Gary Servin |
0:04ac6be8229a | 97 | } u_success; |
Gary Servin |
0:04ac6be8229a | 98 | u_success.real = this->success; |
Gary Servin |
0:04ac6be8229a | 99 | *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 100 | offset += sizeof(this->success); |
Gary Servin |
0:04ac6be8229a | 101 | uint32_t length_status_message = strlen(this->status_message); |
Gary Servin |
0:04ac6be8229a | 102 | varToArr(outbuffer + offset, length_status_message); |
Gary Servin |
0:04ac6be8229a | 103 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 104 | memcpy(outbuffer + offset, this->status_message, length_status_message); |
Gary Servin |
0:04ac6be8229a | 105 | offset += length_status_message; |
Gary Servin |
0:04ac6be8229a | 106 | return offset; |
Gary Servin |
0:04ac6be8229a | 107 | } |
Gary Servin |
0:04ac6be8229a | 108 | |
Gary Servin |
0:04ac6be8229a | 109 | virtual int deserialize(unsigned char *inbuffer) |
Gary Servin |
0:04ac6be8229a | 110 | { |
Gary Servin |
0:04ac6be8229a | 111 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 112 | offset += this->link_state.deserialize(inbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 113 | union { |
Gary Servin |
0:04ac6be8229a | 114 | bool real; |
Gary Servin |
0:04ac6be8229a | 115 | uint8_t base; |
Gary Servin |
0:04ac6be8229a | 116 | } u_success; |
Gary Servin |
0:04ac6be8229a | 117 | u_success.base = 0; |
Gary Servin |
0:04ac6be8229a | 118 | u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
Gary Servin |
0:04ac6be8229a | 119 | this->success = u_success.real; |
Gary Servin |
0:04ac6be8229a | 120 | offset += sizeof(this->success); |
Gary Servin |
0:04ac6be8229a | 121 | uint32_t length_status_message; |
Gary Servin |
0:04ac6be8229a | 122 | arrToVar(length_status_message, (inbuffer + offset)); |
Gary Servin |
0:04ac6be8229a | 123 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 124 | for(unsigned int k= offset; k< offset+length_status_message; ++k){ |
Gary Servin |
0:04ac6be8229a | 125 | inbuffer[k-1]=inbuffer[k]; |
Gary Servin |
0:04ac6be8229a | 126 | } |
Gary Servin |
0:04ac6be8229a | 127 | inbuffer[offset+length_status_message-1]=0; |
Gary Servin |
0:04ac6be8229a | 128 | this->status_message = (char *)(inbuffer + offset-1); |
Gary Servin |
0:04ac6be8229a | 129 | offset += length_status_message; |
Gary Servin |
0:04ac6be8229a | 130 | return offset; |
Gary Servin |
0:04ac6be8229a | 131 | } |
Gary Servin |
0:04ac6be8229a | 132 | |
Gary Servin |
0:04ac6be8229a | 133 | const char * getType(){ return GETLINKSTATE; }; |
Gary Servin |
0:04ac6be8229a | 134 | const char * getMD5(){ return "8ba55ad34f9c072e75c0de57b089753b"; }; |
Gary Servin |
0:04ac6be8229a | 135 | |
Gary Servin |
0:04ac6be8229a | 136 | }; |
Gary Servin |
0:04ac6be8229a | 137 | |
Gary Servin |
0:04ac6be8229a | 138 | class GetLinkState { |
Gary Servin |
0:04ac6be8229a | 139 | public: |
Gary Servin |
0:04ac6be8229a | 140 | typedef GetLinkStateRequest Request; |
Gary Servin |
0:04ac6be8229a | 141 | typedef GetLinkStateResponse Response; |
Gary Servin |
0:04ac6be8229a | 142 | }; |
Gary Servin |
0:04ac6be8229a | 143 | |
Gary Servin |
0:04ac6be8229a | 144 | } |
Gary Servin |
0:04ac6be8229a | 145 | #endif |