rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

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?

UserRevisionLine numberNew contents of line
akashvibhute 0:30537dec6e0b 1 #ifndef _ROS_moveit_msgs_PlaceGoal_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_moveit_msgs_PlaceGoal_h
akashvibhute 0:30537dec6e0b 3
akashvibhute 0:30537dec6e0b 4 #include <stdint.h>
akashvibhute 0:30537dec6e0b 5 #include <string.h>
akashvibhute 0:30537dec6e0b 6 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 7 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 8 #include "moveit_msgs/PlaceLocation.h"
akashvibhute 0:30537dec6e0b 9 #include "moveit_msgs/Constraints.h"
akashvibhute 0:30537dec6e0b 10 #include "moveit_msgs/PlanningOptions.h"
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 namespace moveit_msgs
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 class PlaceGoal : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 const char* group_name;
akashvibhute 0:30537dec6e0b 19 const char* attached_object_name;
akashvibhute 0:30537dec6e0b 20 uint8_t place_locations_length;
akashvibhute 0:30537dec6e0b 21 moveit_msgs::PlaceLocation st_place_locations;
akashvibhute 0:30537dec6e0b 22 moveit_msgs::PlaceLocation * place_locations;
akashvibhute 0:30537dec6e0b 23 bool place_eef;
akashvibhute 0:30537dec6e0b 24 const char* support_surface_name;
akashvibhute 0:30537dec6e0b 25 bool allow_gripper_support_collision;
akashvibhute 0:30537dec6e0b 26 moveit_msgs::Constraints path_constraints;
akashvibhute 0:30537dec6e0b 27 const char* planner_id;
akashvibhute 0:30537dec6e0b 28 uint8_t allowed_touch_objects_length;
akashvibhute 0:30537dec6e0b 29 char* st_allowed_touch_objects;
akashvibhute 0:30537dec6e0b 30 char* * allowed_touch_objects;
akashvibhute 0:30537dec6e0b 31 float allowed_planning_time;
akashvibhute 0:30537dec6e0b 32 moveit_msgs::PlanningOptions planning_options;
akashvibhute 0:30537dec6e0b 33
akashvibhute 0:30537dec6e0b 34 PlaceGoal():
akashvibhute 0:30537dec6e0b 35 group_name(""),
akashvibhute 0:30537dec6e0b 36 attached_object_name(""),
akashvibhute 0:30537dec6e0b 37 place_locations_length(0), place_locations(NULL),
akashvibhute 0:30537dec6e0b 38 place_eef(0),
akashvibhute 0:30537dec6e0b 39 support_surface_name(""),
akashvibhute 0:30537dec6e0b 40 allow_gripper_support_collision(0),
akashvibhute 0:30537dec6e0b 41 path_constraints(),
akashvibhute 0:30537dec6e0b 42 planner_id(""),
akashvibhute 0:30537dec6e0b 43 allowed_touch_objects_length(0), allowed_touch_objects(NULL),
akashvibhute 0:30537dec6e0b 44 allowed_planning_time(0),
akashvibhute 0:30537dec6e0b 45 planning_options()
akashvibhute 0:30537dec6e0b 46 {
akashvibhute 0:30537dec6e0b 47 }
akashvibhute 0:30537dec6e0b 48
akashvibhute 0:30537dec6e0b 49 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 50 {
akashvibhute 0:30537dec6e0b 51 int offset = 0;
akashvibhute 0:30537dec6e0b 52 uint32_t length_group_name = strlen(this->group_name);
akashvibhute 0:30537dec6e0b 53 memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 54 offset += 4;
akashvibhute 0:30537dec6e0b 55 memcpy(outbuffer + offset, this->group_name, length_group_name);
akashvibhute 0:30537dec6e0b 56 offset += length_group_name;
akashvibhute 0:30537dec6e0b 57 uint32_t length_attached_object_name = strlen(this->attached_object_name);
akashvibhute 0:30537dec6e0b 58 memcpy(outbuffer + offset, &length_attached_object_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 59 offset += 4;
akashvibhute 0:30537dec6e0b 60 memcpy(outbuffer + offset, this->attached_object_name, length_attached_object_name);
akashvibhute 0:30537dec6e0b 61 offset += length_attached_object_name;
akashvibhute 0:30537dec6e0b 62 *(outbuffer + offset++) = place_locations_length;
akashvibhute 0:30537dec6e0b 63 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 64 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 65 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 66 for( uint8_t i = 0; i < place_locations_length; i++){
akashvibhute 0:30537dec6e0b 67 offset += this->place_locations[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 68 }
akashvibhute 0:30537dec6e0b 69 union {
akashvibhute 0:30537dec6e0b 70 bool real;
akashvibhute 0:30537dec6e0b 71 uint8_t base;
akashvibhute 0:30537dec6e0b 72 } u_place_eef;
akashvibhute 0:30537dec6e0b 73 u_place_eef.real = this->place_eef;
akashvibhute 0:30537dec6e0b 74 *(outbuffer + offset + 0) = (u_place_eef.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 75 offset += sizeof(this->place_eef);
akashvibhute 0:30537dec6e0b 76 uint32_t length_support_surface_name = strlen(this->support_surface_name);
akashvibhute 0:30537dec6e0b 77 memcpy(outbuffer + offset, &length_support_surface_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 78 offset += 4;
akashvibhute 0:30537dec6e0b 79 memcpy(outbuffer + offset, this->support_surface_name, length_support_surface_name);
akashvibhute 0:30537dec6e0b 80 offset += length_support_surface_name;
akashvibhute 0:30537dec6e0b 81 union {
akashvibhute 0:30537dec6e0b 82 bool real;
akashvibhute 0:30537dec6e0b 83 uint8_t base;
akashvibhute 0:30537dec6e0b 84 } u_allow_gripper_support_collision;
akashvibhute 0:30537dec6e0b 85 u_allow_gripper_support_collision.real = this->allow_gripper_support_collision;
akashvibhute 0:30537dec6e0b 86 *(outbuffer + offset + 0) = (u_allow_gripper_support_collision.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 87 offset += sizeof(this->allow_gripper_support_collision);
akashvibhute 0:30537dec6e0b 88 offset += this->path_constraints.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 89 uint32_t length_planner_id = strlen(this->planner_id);
akashvibhute 0:30537dec6e0b 90 memcpy(outbuffer + offset, &length_planner_id, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 91 offset += 4;
akashvibhute 0:30537dec6e0b 92 memcpy(outbuffer + offset, this->planner_id, length_planner_id);
akashvibhute 0:30537dec6e0b 93 offset += length_planner_id;
akashvibhute 0:30537dec6e0b 94 *(outbuffer + offset++) = allowed_touch_objects_length;
akashvibhute 0:30537dec6e0b 95 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 96 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 97 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 98 for( uint8_t i = 0; i < allowed_touch_objects_length; i++){
akashvibhute 0:30537dec6e0b 99 uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]);
akashvibhute 0:30537dec6e0b 100 memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 101 offset += 4;
akashvibhute 0:30537dec6e0b 102 memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi);
akashvibhute 0:30537dec6e0b 103 offset += length_allowed_touch_objectsi;
akashvibhute 0:30537dec6e0b 104 }
akashvibhute 0:30537dec6e0b 105 offset += serializeAvrFloat64(outbuffer + offset, this->allowed_planning_time);
akashvibhute 0:30537dec6e0b 106 offset += this->planning_options.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 107 return offset;
akashvibhute 0:30537dec6e0b 108 }
akashvibhute 0:30537dec6e0b 109
akashvibhute 0:30537dec6e0b 110 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 111 {
akashvibhute 0:30537dec6e0b 112 int offset = 0;
akashvibhute 0:30537dec6e0b 113 uint32_t length_group_name;
akashvibhute 0:30537dec6e0b 114 memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 115 offset += 4;
akashvibhute 0:30537dec6e0b 116 for(unsigned int k= offset; k< offset+length_group_name; ++k){
akashvibhute 0:30537dec6e0b 117 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 118 }
akashvibhute 0:30537dec6e0b 119 inbuffer[offset+length_group_name-1]=0;
akashvibhute 0:30537dec6e0b 120 this->group_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 121 offset += length_group_name;
akashvibhute 0:30537dec6e0b 122 uint32_t length_attached_object_name;
akashvibhute 0:30537dec6e0b 123 memcpy(&length_attached_object_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 124 offset += 4;
akashvibhute 0:30537dec6e0b 125 for(unsigned int k= offset; k< offset+length_attached_object_name; ++k){
akashvibhute 0:30537dec6e0b 126 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 127 }
akashvibhute 0:30537dec6e0b 128 inbuffer[offset+length_attached_object_name-1]=0;
akashvibhute 0:30537dec6e0b 129 this->attached_object_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 130 offset += length_attached_object_name;
akashvibhute 0:30537dec6e0b 131 uint8_t place_locations_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 132 if(place_locations_lengthT > place_locations_length)
akashvibhute 0:30537dec6e0b 133 this->place_locations = (moveit_msgs::PlaceLocation*)realloc(this->place_locations, place_locations_lengthT * sizeof(moveit_msgs::PlaceLocation));
akashvibhute 0:30537dec6e0b 134 offset += 3;
akashvibhute 0:30537dec6e0b 135 place_locations_length = place_locations_lengthT;
akashvibhute 0:30537dec6e0b 136 for( uint8_t i = 0; i < place_locations_length; i++){
akashvibhute 0:30537dec6e0b 137 offset += this->st_place_locations.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 138 memcpy( &(this->place_locations[i]), &(this->st_place_locations), sizeof(moveit_msgs::PlaceLocation));
akashvibhute 0:30537dec6e0b 139 }
akashvibhute 0:30537dec6e0b 140 union {
akashvibhute 0:30537dec6e0b 141 bool real;
akashvibhute 0:30537dec6e0b 142 uint8_t base;
akashvibhute 0:30537dec6e0b 143 } u_place_eef;
akashvibhute 0:30537dec6e0b 144 u_place_eef.base = 0;
akashvibhute 0:30537dec6e0b 145 u_place_eef.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 146 this->place_eef = u_place_eef.real;
akashvibhute 0:30537dec6e0b 147 offset += sizeof(this->place_eef);
akashvibhute 0:30537dec6e0b 148 uint32_t length_support_surface_name;
akashvibhute 0:30537dec6e0b 149 memcpy(&length_support_surface_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 150 offset += 4;
akashvibhute 0:30537dec6e0b 151 for(unsigned int k= offset; k< offset+length_support_surface_name; ++k){
akashvibhute 0:30537dec6e0b 152 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 153 }
akashvibhute 0:30537dec6e0b 154 inbuffer[offset+length_support_surface_name-1]=0;
akashvibhute 0:30537dec6e0b 155 this->support_surface_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 156 offset += length_support_surface_name;
akashvibhute 0:30537dec6e0b 157 union {
akashvibhute 0:30537dec6e0b 158 bool real;
akashvibhute 0:30537dec6e0b 159 uint8_t base;
akashvibhute 0:30537dec6e0b 160 } u_allow_gripper_support_collision;
akashvibhute 0:30537dec6e0b 161 u_allow_gripper_support_collision.base = 0;
akashvibhute 0:30537dec6e0b 162 u_allow_gripper_support_collision.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 163 this->allow_gripper_support_collision = u_allow_gripper_support_collision.real;
akashvibhute 0:30537dec6e0b 164 offset += sizeof(this->allow_gripper_support_collision);
akashvibhute 0:30537dec6e0b 165 offset += this->path_constraints.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 166 uint32_t length_planner_id;
akashvibhute 0:30537dec6e0b 167 memcpy(&length_planner_id, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 168 offset += 4;
akashvibhute 0:30537dec6e0b 169 for(unsigned int k= offset; k< offset+length_planner_id; ++k){
akashvibhute 0:30537dec6e0b 170 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 171 }
akashvibhute 0:30537dec6e0b 172 inbuffer[offset+length_planner_id-1]=0;
akashvibhute 0:30537dec6e0b 173 this->planner_id = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 174 offset += length_planner_id;
akashvibhute 0:30537dec6e0b 175 uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 176 if(allowed_touch_objects_lengthT > allowed_touch_objects_length)
akashvibhute 0:30537dec6e0b 177 this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 178 offset += 3;
akashvibhute 0:30537dec6e0b 179 allowed_touch_objects_length = allowed_touch_objects_lengthT;
akashvibhute 0:30537dec6e0b 180 for( uint8_t i = 0; i < allowed_touch_objects_length; i++){
akashvibhute 0:30537dec6e0b 181 uint32_t length_st_allowed_touch_objects;
akashvibhute 0:30537dec6e0b 182 memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 183 offset += 4;
akashvibhute 0:30537dec6e0b 184 for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){
akashvibhute 0:30537dec6e0b 185 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 186 }
akashvibhute 0:30537dec6e0b 187 inbuffer[offset+length_st_allowed_touch_objects-1]=0;
akashvibhute 0:30537dec6e0b 188 this->st_allowed_touch_objects = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 189 offset += length_st_allowed_touch_objects;
akashvibhute 0:30537dec6e0b 190 memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*));
akashvibhute 0:30537dec6e0b 191 }
akashvibhute 0:30537dec6e0b 192 offset += deserializeAvrFloat64(inbuffer + offset, &(this->allowed_planning_time));
akashvibhute 0:30537dec6e0b 193 offset += this->planning_options.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 194 return offset;
akashvibhute 0:30537dec6e0b 195 }
akashvibhute 0:30537dec6e0b 196
akashvibhute 0:30537dec6e0b 197 const char * getType(){ return "moveit_msgs/PlaceGoal"; };
akashvibhute 0:30537dec6e0b 198 const char * getMD5(){ return "e3f3e956e536ccd313fd8f23023f0a94"; };
akashvibhute 0:30537dec6e0b 199
akashvibhute 0:30537dec6e0b 200 };
akashvibhute 0:30537dec6e0b 201
akashvibhute 0:30537dec6e0b 202 }
akashvibhute 0:30537dec6e0b 203 #endif