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_BoundingVolume_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_moveit_msgs_BoundingVolume_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 "shape_msgs/SolidPrimitive.h"
akashvibhute 0:30537dec6e0b 9 #include "geometry_msgs/Pose.h"
akashvibhute 0:30537dec6e0b 10 #include "shape_msgs/Mesh.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 BoundingVolume : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 uint8_t primitives_length;
akashvibhute 0:30537dec6e0b 19 shape_msgs::SolidPrimitive st_primitives;
akashvibhute 0:30537dec6e0b 20 shape_msgs::SolidPrimitive * primitives;
akashvibhute 0:30537dec6e0b 21 uint8_t primitive_poses_length;
akashvibhute 0:30537dec6e0b 22 geometry_msgs::Pose st_primitive_poses;
akashvibhute 0:30537dec6e0b 23 geometry_msgs::Pose * primitive_poses;
akashvibhute 0:30537dec6e0b 24 uint8_t meshes_length;
akashvibhute 0:30537dec6e0b 25 shape_msgs::Mesh st_meshes;
akashvibhute 0:30537dec6e0b 26 shape_msgs::Mesh * meshes;
akashvibhute 0:30537dec6e0b 27 uint8_t mesh_poses_length;
akashvibhute 0:30537dec6e0b 28 geometry_msgs::Pose st_mesh_poses;
akashvibhute 0:30537dec6e0b 29 geometry_msgs::Pose * mesh_poses;
akashvibhute 0:30537dec6e0b 30
akashvibhute 0:30537dec6e0b 31 BoundingVolume():
akashvibhute 0:30537dec6e0b 32 primitives_length(0), primitives(NULL),
akashvibhute 0:30537dec6e0b 33 primitive_poses_length(0), primitive_poses(NULL),
akashvibhute 0:30537dec6e0b 34 meshes_length(0), meshes(NULL),
akashvibhute 0:30537dec6e0b 35 mesh_poses_length(0), mesh_poses(NULL)
akashvibhute 0:30537dec6e0b 36 {
akashvibhute 0:30537dec6e0b 37 }
akashvibhute 0:30537dec6e0b 38
akashvibhute 0:30537dec6e0b 39 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 40 {
akashvibhute 0:30537dec6e0b 41 int offset = 0;
akashvibhute 0:30537dec6e0b 42 *(outbuffer + offset++) = primitives_length;
akashvibhute 0:30537dec6e0b 43 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 44 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 45 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 46 for( uint8_t i = 0; i < primitives_length; i++){
akashvibhute 0:30537dec6e0b 47 offset += this->primitives[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 48 }
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset++) = primitive_poses_length;
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 51 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 53 for( uint8_t i = 0; i < primitive_poses_length; i++){
akashvibhute 0:30537dec6e0b 54 offset += this->primitive_poses[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 55 }
akashvibhute 0:30537dec6e0b 56 *(outbuffer + offset++) = meshes_length;
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 58 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 59 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 60 for( uint8_t i = 0; i < meshes_length; i++){
akashvibhute 0:30537dec6e0b 61 offset += this->meshes[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 62 }
akashvibhute 0:30537dec6e0b 63 *(outbuffer + offset++) = mesh_poses_length;
akashvibhute 0:30537dec6e0b 64 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 65 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 66 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 67 for( uint8_t i = 0; i < mesh_poses_length; i++){
akashvibhute 0:30537dec6e0b 68 offset += this->mesh_poses[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 69 }
akashvibhute 0:30537dec6e0b 70 return offset;
akashvibhute 0:30537dec6e0b 71 }
akashvibhute 0:30537dec6e0b 72
akashvibhute 0:30537dec6e0b 73 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 74 {
akashvibhute 0:30537dec6e0b 75 int offset = 0;
akashvibhute 0:30537dec6e0b 76 uint8_t primitives_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 77 if(primitives_lengthT > primitives_length)
akashvibhute 0:30537dec6e0b 78 this->primitives = (shape_msgs::SolidPrimitive*)realloc(this->primitives, primitives_lengthT * sizeof(shape_msgs::SolidPrimitive));
akashvibhute 0:30537dec6e0b 79 offset += 3;
akashvibhute 0:30537dec6e0b 80 primitives_length = primitives_lengthT;
akashvibhute 0:30537dec6e0b 81 for( uint8_t i = 0; i < primitives_length; i++){
akashvibhute 0:30537dec6e0b 82 offset += this->st_primitives.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 83 memcpy( &(this->primitives[i]), &(this->st_primitives), sizeof(shape_msgs::SolidPrimitive));
akashvibhute 0:30537dec6e0b 84 }
akashvibhute 0:30537dec6e0b 85 uint8_t primitive_poses_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 86 if(primitive_poses_lengthT > primitive_poses_length)
akashvibhute 0:30537dec6e0b 87 this->primitive_poses = (geometry_msgs::Pose*)realloc(this->primitive_poses, primitive_poses_lengthT * sizeof(geometry_msgs::Pose));
akashvibhute 0:30537dec6e0b 88 offset += 3;
akashvibhute 0:30537dec6e0b 89 primitive_poses_length = primitive_poses_lengthT;
akashvibhute 0:30537dec6e0b 90 for( uint8_t i = 0; i < primitive_poses_length; i++){
akashvibhute 0:30537dec6e0b 91 offset += this->st_primitive_poses.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 92 memcpy( &(this->primitive_poses[i]), &(this->st_primitive_poses), sizeof(geometry_msgs::Pose));
akashvibhute 0:30537dec6e0b 93 }
akashvibhute 0:30537dec6e0b 94 uint8_t meshes_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 95 if(meshes_lengthT > meshes_length)
akashvibhute 0:30537dec6e0b 96 this->meshes = (shape_msgs::Mesh*)realloc(this->meshes, meshes_lengthT * sizeof(shape_msgs::Mesh));
akashvibhute 0:30537dec6e0b 97 offset += 3;
akashvibhute 0:30537dec6e0b 98 meshes_length = meshes_lengthT;
akashvibhute 0:30537dec6e0b 99 for( uint8_t i = 0; i < meshes_length; i++){
akashvibhute 0:30537dec6e0b 100 offset += this->st_meshes.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 101 memcpy( &(this->meshes[i]), &(this->st_meshes), sizeof(shape_msgs::Mesh));
akashvibhute 0:30537dec6e0b 102 }
akashvibhute 0:30537dec6e0b 103 uint8_t mesh_poses_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 104 if(mesh_poses_lengthT > mesh_poses_length)
akashvibhute 0:30537dec6e0b 105 this->mesh_poses = (geometry_msgs::Pose*)realloc(this->mesh_poses, mesh_poses_lengthT * sizeof(geometry_msgs::Pose));
akashvibhute 0:30537dec6e0b 106 offset += 3;
akashvibhute 0:30537dec6e0b 107 mesh_poses_length = mesh_poses_lengthT;
akashvibhute 0:30537dec6e0b 108 for( uint8_t i = 0; i < mesh_poses_length; i++){
akashvibhute 0:30537dec6e0b 109 offset += this->st_mesh_poses.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 110 memcpy( &(this->mesh_poses[i]), &(this->st_mesh_poses), sizeof(geometry_msgs::Pose));
akashvibhute 0:30537dec6e0b 111 }
akashvibhute 0:30537dec6e0b 112 return offset;
akashvibhute 0:30537dec6e0b 113 }
akashvibhute 0:30537dec6e0b 114
akashvibhute 0:30537dec6e0b 115 const char * getType(){ return "moveit_msgs/BoundingVolume"; };
akashvibhute 0:30537dec6e0b 116 const char * getMD5(){ return "22db94010f39e9198032cb4a1aeda26e"; };
akashvibhute 0:30537dec6e0b 117
akashvibhute 0:30537dec6e0b 118 };
akashvibhute 0:30537dec6e0b 119
akashvibhute 0:30537dec6e0b 120 }
akashvibhute 0:30537dec6e0b 121 #endif