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_manipulation_msgs_GraspPlanningGoal_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_manipulation_msgs_GraspPlanningGoal_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 "manipulation_msgs/GraspableObject.h"
akashvibhute 0:30537dec6e0b 9 #include "manipulation_msgs/Grasp.h"
akashvibhute 0:30537dec6e0b 10
akashvibhute 0:30537dec6e0b 11 namespace manipulation_msgs
akashvibhute 0:30537dec6e0b 12 {
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 class GraspPlanningGoal : public ros::Msg
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16 public:
akashvibhute 0:30537dec6e0b 17 const char* arm_name;
akashvibhute 0:30537dec6e0b 18 manipulation_msgs::GraspableObject target;
akashvibhute 0:30537dec6e0b 19 const char* collision_object_name;
akashvibhute 0:30537dec6e0b 20 const char* collision_support_surface_name;
akashvibhute 0:30537dec6e0b 21 uint8_t grasps_to_evaluate_length;
akashvibhute 0:30537dec6e0b 22 manipulation_msgs::Grasp st_grasps_to_evaluate;
akashvibhute 0:30537dec6e0b 23 manipulation_msgs::Grasp * grasps_to_evaluate;
akashvibhute 0:30537dec6e0b 24 uint8_t movable_obstacles_length;
akashvibhute 0:30537dec6e0b 25 manipulation_msgs::GraspableObject st_movable_obstacles;
akashvibhute 0:30537dec6e0b 26 manipulation_msgs::GraspableObject * movable_obstacles;
akashvibhute 0:30537dec6e0b 27
akashvibhute 0:30537dec6e0b 28 GraspPlanningGoal():
akashvibhute 0:30537dec6e0b 29 arm_name(""),
akashvibhute 0:30537dec6e0b 30 target(),
akashvibhute 0:30537dec6e0b 31 collision_object_name(""),
akashvibhute 0:30537dec6e0b 32 collision_support_surface_name(""),
akashvibhute 0:30537dec6e0b 33 grasps_to_evaluate_length(0), grasps_to_evaluate(NULL),
akashvibhute 0:30537dec6e0b 34 movable_obstacles_length(0), movable_obstacles(NULL)
akashvibhute 0:30537dec6e0b 35 {
akashvibhute 0:30537dec6e0b 36 }
akashvibhute 0:30537dec6e0b 37
akashvibhute 0:30537dec6e0b 38 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 39 {
akashvibhute 0:30537dec6e0b 40 int offset = 0;
akashvibhute 0:30537dec6e0b 41 uint32_t length_arm_name = strlen(this->arm_name);
akashvibhute 0:30537dec6e0b 42 memcpy(outbuffer + offset, &length_arm_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 43 offset += 4;
akashvibhute 0:30537dec6e0b 44 memcpy(outbuffer + offset, this->arm_name, length_arm_name);
akashvibhute 0:30537dec6e0b 45 offset += length_arm_name;
akashvibhute 0:30537dec6e0b 46 offset += this->target.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 47 uint32_t length_collision_object_name = strlen(this->collision_object_name);
akashvibhute 0:30537dec6e0b 48 memcpy(outbuffer + offset, &length_collision_object_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 49 offset += 4;
akashvibhute 0:30537dec6e0b 50 memcpy(outbuffer + offset, this->collision_object_name, length_collision_object_name);
akashvibhute 0:30537dec6e0b 51 offset += length_collision_object_name;
akashvibhute 0:30537dec6e0b 52 uint32_t length_collision_support_surface_name = strlen(this->collision_support_surface_name);
akashvibhute 0:30537dec6e0b 53 memcpy(outbuffer + offset, &length_collision_support_surface_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 54 offset += 4;
akashvibhute 0:30537dec6e0b 55 memcpy(outbuffer + offset, this->collision_support_surface_name, length_collision_support_surface_name);
akashvibhute 0:30537dec6e0b 56 offset += length_collision_support_surface_name;
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset++) = grasps_to_evaluate_length;
akashvibhute 0:30537dec6e0b 58 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 59 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 60 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 61 for( uint8_t i = 0; i < grasps_to_evaluate_length; i++){
akashvibhute 0:30537dec6e0b 62 offset += this->grasps_to_evaluate[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 63 }
akashvibhute 0:30537dec6e0b 64 *(outbuffer + offset++) = movable_obstacles_length;
akashvibhute 0:30537dec6e0b 65 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 66 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 67 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 68 for( uint8_t i = 0; i < movable_obstacles_length; i++){
akashvibhute 0:30537dec6e0b 69 offset += this->movable_obstacles[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 70 }
akashvibhute 0:30537dec6e0b 71 return offset;
akashvibhute 0:30537dec6e0b 72 }
akashvibhute 0:30537dec6e0b 73
akashvibhute 0:30537dec6e0b 74 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 75 {
akashvibhute 0:30537dec6e0b 76 int offset = 0;
akashvibhute 0:30537dec6e0b 77 uint32_t length_arm_name;
akashvibhute 0:30537dec6e0b 78 memcpy(&length_arm_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 79 offset += 4;
akashvibhute 0:30537dec6e0b 80 for(unsigned int k= offset; k< offset+length_arm_name; ++k){
akashvibhute 0:30537dec6e0b 81 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 82 }
akashvibhute 0:30537dec6e0b 83 inbuffer[offset+length_arm_name-1]=0;
akashvibhute 0:30537dec6e0b 84 this->arm_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 85 offset += length_arm_name;
akashvibhute 0:30537dec6e0b 86 offset += this->target.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 87 uint32_t length_collision_object_name;
akashvibhute 0:30537dec6e0b 88 memcpy(&length_collision_object_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 89 offset += 4;
akashvibhute 0:30537dec6e0b 90 for(unsigned int k= offset; k< offset+length_collision_object_name; ++k){
akashvibhute 0:30537dec6e0b 91 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 92 }
akashvibhute 0:30537dec6e0b 93 inbuffer[offset+length_collision_object_name-1]=0;
akashvibhute 0:30537dec6e0b 94 this->collision_object_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 95 offset += length_collision_object_name;
akashvibhute 0:30537dec6e0b 96 uint32_t length_collision_support_surface_name;
akashvibhute 0:30537dec6e0b 97 memcpy(&length_collision_support_surface_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 98 offset += 4;
akashvibhute 0:30537dec6e0b 99 for(unsigned int k= offset; k< offset+length_collision_support_surface_name; ++k){
akashvibhute 0:30537dec6e0b 100 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 101 }
akashvibhute 0:30537dec6e0b 102 inbuffer[offset+length_collision_support_surface_name-1]=0;
akashvibhute 0:30537dec6e0b 103 this->collision_support_surface_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 104 offset += length_collision_support_surface_name;
akashvibhute 0:30537dec6e0b 105 uint8_t grasps_to_evaluate_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 106 if(grasps_to_evaluate_lengthT > grasps_to_evaluate_length)
akashvibhute 0:30537dec6e0b 107 this->grasps_to_evaluate = (manipulation_msgs::Grasp*)realloc(this->grasps_to_evaluate, grasps_to_evaluate_lengthT * sizeof(manipulation_msgs::Grasp));
akashvibhute 0:30537dec6e0b 108 offset += 3;
akashvibhute 0:30537dec6e0b 109 grasps_to_evaluate_length = grasps_to_evaluate_lengthT;
akashvibhute 0:30537dec6e0b 110 for( uint8_t i = 0; i < grasps_to_evaluate_length; i++){
akashvibhute 0:30537dec6e0b 111 offset += this->st_grasps_to_evaluate.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 112 memcpy( &(this->grasps_to_evaluate[i]), &(this->st_grasps_to_evaluate), sizeof(manipulation_msgs::Grasp));
akashvibhute 0:30537dec6e0b 113 }
akashvibhute 0:30537dec6e0b 114 uint8_t movable_obstacles_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 115 if(movable_obstacles_lengthT > movable_obstacles_length)
akashvibhute 0:30537dec6e0b 116 this->movable_obstacles = (manipulation_msgs::GraspableObject*)realloc(this->movable_obstacles, movable_obstacles_lengthT * sizeof(manipulation_msgs::GraspableObject));
akashvibhute 0:30537dec6e0b 117 offset += 3;
akashvibhute 0:30537dec6e0b 118 movable_obstacles_length = movable_obstacles_lengthT;
akashvibhute 0:30537dec6e0b 119 for( uint8_t i = 0; i < movable_obstacles_length; i++){
akashvibhute 0:30537dec6e0b 120 offset += this->st_movable_obstacles.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 121 memcpy( &(this->movable_obstacles[i]), &(this->st_movable_obstacles), sizeof(manipulation_msgs::GraspableObject));
akashvibhute 0:30537dec6e0b 122 }
akashvibhute 0:30537dec6e0b 123 return offset;
akashvibhute 0:30537dec6e0b 124 }
akashvibhute 0:30537dec6e0b 125
akashvibhute 0:30537dec6e0b 126 const char * getType(){ return "manipulation_msgs/GraspPlanningGoal"; };
akashvibhute 0:30537dec6e0b 127 const char * getMD5(){ return "077dca08a07415d82d6ab047890161f4"; };
akashvibhute 0:30537dec6e0b 128
akashvibhute 0:30537dec6e0b 129 };
akashvibhute 0:30537dec6e0b 130
akashvibhute 0:30537dec6e0b 131 }
akashvibhute 0:30537dec6e0b 132 #endif