rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
moveit_msgs/GetStateValidity.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_GetStateValidity_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_SERVICE_GetStateValidity_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 "moveit_msgs/ConstraintEvalResult.h" |
akashvibhute | 0:30537dec6e0b | 8 | #include "moveit_msgs/CostSource.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "moveit_msgs/ContactInformation.h" |
akashvibhute | 0:30537dec6e0b | 10 | #include "moveit_msgs/RobotState.h" |
akashvibhute | 0:30537dec6e0b | 11 | #include "moveit_msgs/Constraints.h" |
akashvibhute | 0:30537dec6e0b | 12 | |
akashvibhute | 0:30537dec6e0b | 13 | namespace moveit_msgs |
akashvibhute | 0:30537dec6e0b | 14 | { |
akashvibhute | 0:30537dec6e0b | 15 | |
akashvibhute | 0:30537dec6e0b | 16 | static const char GETSTATEVALIDITY[] = "moveit_msgs/GetStateValidity"; |
akashvibhute | 0:30537dec6e0b | 17 | |
akashvibhute | 0:30537dec6e0b | 18 | class GetStateValidityRequest : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 19 | { |
akashvibhute | 0:30537dec6e0b | 20 | public: |
akashvibhute | 0:30537dec6e0b | 21 | moveit_msgs::RobotState robot_state; |
akashvibhute | 0:30537dec6e0b | 22 | const char* group_name; |
akashvibhute | 0:30537dec6e0b | 23 | moveit_msgs::Constraints constraints; |
akashvibhute | 0:30537dec6e0b | 24 | |
akashvibhute | 0:30537dec6e0b | 25 | GetStateValidityRequest(): |
akashvibhute | 0:30537dec6e0b | 26 | robot_state(), |
akashvibhute | 0:30537dec6e0b | 27 | group_name(""), |
akashvibhute | 0:30537dec6e0b | 28 | constraints() |
akashvibhute | 0:30537dec6e0b | 29 | { |
akashvibhute | 0:30537dec6e0b | 30 | } |
akashvibhute | 0:30537dec6e0b | 31 | |
akashvibhute | 0:30537dec6e0b | 32 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 33 | { |
akashvibhute | 0:30537dec6e0b | 34 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 35 | offset += this->robot_state.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 36 | uint32_t length_group_name = strlen(this->group_name); |
akashvibhute | 0:30537dec6e0b | 37 | memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 38 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 39 | memcpy(outbuffer + offset, this->group_name, length_group_name); |
akashvibhute | 0:30537dec6e0b | 40 | offset += length_group_name; |
akashvibhute | 0:30537dec6e0b | 41 | offset += this->constraints.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 42 | return offset; |
akashvibhute | 0:30537dec6e0b | 43 | } |
akashvibhute | 0:30537dec6e0b | 44 | |
akashvibhute | 0:30537dec6e0b | 45 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 46 | { |
akashvibhute | 0:30537dec6e0b | 47 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 48 | offset += this->robot_state.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 49 | uint32_t length_group_name; |
akashvibhute | 0:30537dec6e0b | 50 | memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 51 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 52 | for(unsigned int k= offset; k< offset+length_group_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 53 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 54 | } |
akashvibhute | 0:30537dec6e0b | 55 | inbuffer[offset+length_group_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 56 | this->group_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 57 | offset += length_group_name; |
akashvibhute | 0:30537dec6e0b | 58 | offset += this->constraints.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 59 | return offset; |
akashvibhute | 0:30537dec6e0b | 60 | } |
akashvibhute | 0:30537dec6e0b | 61 | |
akashvibhute | 0:30537dec6e0b | 62 | const char * getType(){ return GETSTATEVALIDITY; }; |
akashvibhute | 0:30537dec6e0b | 63 | const char * getMD5(){ return "b569c609cafad20ba7d0e46e70e7cab1"; }; |
akashvibhute | 0:30537dec6e0b | 64 | |
akashvibhute | 0:30537dec6e0b | 65 | }; |
akashvibhute | 0:30537dec6e0b | 66 | |
akashvibhute | 0:30537dec6e0b | 67 | class GetStateValidityResponse : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 68 | { |
akashvibhute | 0:30537dec6e0b | 69 | public: |
akashvibhute | 0:30537dec6e0b | 70 | bool valid; |
akashvibhute | 0:30537dec6e0b | 71 | uint8_t contacts_length; |
akashvibhute | 0:30537dec6e0b | 72 | moveit_msgs::ContactInformation st_contacts; |
akashvibhute | 0:30537dec6e0b | 73 | moveit_msgs::ContactInformation * contacts; |
akashvibhute | 0:30537dec6e0b | 74 | uint8_t cost_sources_length; |
akashvibhute | 0:30537dec6e0b | 75 | moveit_msgs::CostSource st_cost_sources; |
akashvibhute | 0:30537dec6e0b | 76 | moveit_msgs::CostSource * cost_sources; |
akashvibhute | 0:30537dec6e0b | 77 | uint8_t constraint_result_length; |
akashvibhute | 0:30537dec6e0b | 78 | moveit_msgs::ConstraintEvalResult st_constraint_result; |
akashvibhute | 0:30537dec6e0b | 79 | moveit_msgs::ConstraintEvalResult * constraint_result; |
akashvibhute | 0:30537dec6e0b | 80 | |
akashvibhute | 0:30537dec6e0b | 81 | GetStateValidityResponse(): |
akashvibhute | 0:30537dec6e0b | 82 | valid(0), |
akashvibhute | 0:30537dec6e0b | 83 | contacts_length(0), contacts(NULL), |
akashvibhute | 0:30537dec6e0b | 84 | cost_sources_length(0), cost_sources(NULL), |
akashvibhute | 0:30537dec6e0b | 85 | constraint_result_length(0), constraint_result(NULL) |
akashvibhute | 0:30537dec6e0b | 86 | { |
akashvibhute | 0:30537dec6e0b | 87 | } |
akashvibhute | 0:30537dec6e0b | 88 | |
akashvibhute | 0:30537dec6e0b | 89 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 90 | { |
akashvibhute | 0:30537dec6e0b | 91 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 92 | union { |
akashvibhute | 0:30537dec6e0b | 93 | bool real; |
akashvibhute | 0:30537dec6e0b | 94 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 95 | } u_valid; |
akashvibhute | 0:30537dec6e0b | 96 | u_valid.real = this->valid; |
akashvibhute | 0:30537dec6e0b | 97 | *(outbuffer + offset + 0) = (u_valid.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 98 | offset += sizeof(this->valid); |
akashvibhute | 0:30537dec6e0b | 99 | *(outbuffer + offset++) = contacts_length; |
akashvibhute | 0:30537dec6e0b | 100 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 101 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 102 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 103 | for( uint8_t i = 0; i < contacts_length; i++){ |
akashvibhute | 0:30537dec6e0b | 104 | offset += this->contacts[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 105 | } |
akashvibhute | 0:30537dec6e0b | 106 | *(outbuffer + offset++) = cost_sources_length; |
akashvibhute | 0:30537dec6e0b | 107 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 108 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 109 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 110 | for( uint8_t i = 0; i < cost_sources_length; i++){ |
akashvibhute | 0:30537dec6e0b | 111 | offset += this->cost_sources[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 112 | } |
akashvibhute | 0:30537dec6e0b | 113 | *(outbuffer + offset++) = constraint_result_length; |
akashvibhute | 0:30537dec6e0b | 114 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 115 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 116 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 117 | for( uint8_t i = 0; i < constraint_result_length; i++){ |
akashvibhute | 0:30537dec6e0b | 118 | offset += this->constraint_result[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 119 | } |
akashvibhute | 0:30537dec6e0b | 120 | return offset; |
akashvibhute | 0:30537dec6e0b | 121 | } |
akashvibhute | 0:30537dec6e0b | 122 | |
akashvibhute | 0:30537dec6e0b | 123 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 124 | { |
akashvibhute | 0:30537dec6e0b | 125 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 126 | union { |
akashvibhute | 0:30537dec6e0b | 127 | bool real; |
akashvibhute | 0:30537dec6e0b | 128 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 129 | } u_valid; |
akashvibhute | 0:30537dec6e0b | 130 | u_valid.base = 0; |
akashvibhute | 0:30537dec6e0b | 131 | u_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 132 | this->valid = u_valid.real; |
akashvibhute | 0:30537dec6e0b | 133 | offset += sizeof(this->valid); |
akashvibhute | 0:30537dec6e0b | 134 | uint8_t contacts_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 135 | if(contacts_lengthT > contacts_length) |
akashvibhute | 0:30537dec6e0b | 136 | this->contacts = (moveit_msgs::ContactInformation*)realloc(this->contacts, contacts_lengthT * sizeof(moveit_msgs::ContactInformation)); |
akashvibhute | 0:30537dec6e0b | 137 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 138 | contacts_length = contacts_lengthT; |
akashvibhute | 0:30537dec6e0b | 139 | for( uint8_t i = 0; i < contacts_length; i++){ |
akashvibhute | 0:30537dec6e0b | 140 | offset += this->st_contacts.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 141 | memcpy( &(this->contacts[i]), &(this->st_contacts), sizeof(moveit_msgs::ContactInformation)); |
akashvibhute | 0:30537dec6e0b | 142 | } |
akashvibhute | 0:30537dec6e0b | 143 | uint8_t cost_sources_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 144 | if(cost_sources_lengthT > cost_sources_length) |
akashvibhute | 0:30537dec6e0b | 145 | this->cost_sources = (moveit_msgs::CostSource*)realloc(this->cost_sources, cost_sources_lengthT * sizeof(moveit_msgs::CostSource)); |
akashvibhute | 0:30537dec6e0b | 146 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 147 | cost_sources_length = cost_sources_lengthT; |
akashvibhute | 0:30537dec6e0b | 148 | for( uint8_t i = 0; i < cost_sources_length; i++){ |
akashvibhute | 0:30537dec6e0b | 149 | offset += this->st_cost_sources.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 150 | memcpy( &(this->cost_sources[i]), &(this->st_cost_sources), sizeof(moveit_msgs::CostSource)); |
akashvibhute | 0:30537dec6e0b | 151 | } |
akashvibhute | 0:30537dec6e0b | 152 | uint8_t constraint_result_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 153 | if(constraint_result_lengthT > constraint_result_length) |
akashvibhute | 0:30537dec6e0b | 154 | this->constraint_result = (moveit_msgs::ConstraintEvalResult*)realloc(this->constraint_result, constraint_result_lengthT * sizeof(moveit_msgs::ConstraintEvalResult)); |
akashvibhute | 0:30537dec6e0b | 155 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 156 | constraint_result_length = constraint_result_lengthT; |
akashvibhute | 0:30537dec6e0b | 157 | for( uint8_t i = 0; i < constraint_result_length; i++){ |
akashvibhute | 0:30537dec6e0b | 158 | offset += this->st_constraint_result.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 159 | memcpy( &(this->constraint_result[i]), &(this->st_constraint_result), sizeof(moveit_msgs::ConstraintEvalResult)); |
akashvibhute | 0:30537dec6e0b | 160 | } |
akashvibhute | 0:30537dec6e0b | 161 | return offset; |
akashvibhute | 0:30537dec6e0b | 162 | } |
akashvibhute | 0:30537dec6e0b | 163 | |
akashvibhute | 0:30537dec6e0b | 164 | const char * getType(){ return GETSTATEVALIDITY; }; |
akashvibhute | 0:30537dec6e0b | 165 | const char * getMD5(){ return "e326fb22b7448f29c0e726d9270d9929"; }; |
akashvibhute | 0:30537dec6e0b | 166 | |
akashvibhute | 0:30537dec6e0b | 167 | }; |
akashvibhute | 0:30537dec6e0b | 168 | |
akashvibhute | 0:30537dec6e0b | 169 | class GetStateValidity { |
akashvibhute | 0:30537dec6e0b | 170 | public: |
akashvibhute | 0:30537dec6e0b | 171 | typedef GetStateValidityRequest Request; |
akashvibhute | 0:30537dec6e0b | 172 | typedef GetStateValidityResponse Response; |
akashvibhute | 0:30537dec6e0b | 173 | }; |
akashvibhute | 0:30537dec6e0b | 174 | |
akashvibhute | 0:30537dec6e0b | 175 | } |
akashvibhute | 0:30537dec6e0b | 176 | #endif |
akashvibhute | 0:30537dec6e0b | 177 |