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_SERVICE_MakeNavPlan_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_SERVICE_MakeNavPlan_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 "geometry_msgs/PoseStamped.h"
akashvibhute 0:30537dec6e0b 8
akashvibhute 0:30537dec6e0b 9 namespace navfn
akashvibhute 0:30537dec6e0b 10 {
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 static const char MAKENAVPLAN[] = "navfn/MakeNavPlan";
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 class MakeNavPlanRequest : public ros::Msg
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16 public:
akashvibhute 0:30537dec6e0b 17 geometry_msgs::PoseStamped start;
akashvibhute 0:30537dec6e0b 18 geometry_msgs::PoseStamped goal;
akashvibhute 0:30537dec6e0b 19
akashvibhute 0:30537dec6e0b 20 MakeNavPlanRequest():
akashvibhute 0:30537dec6e0b 21 start(),
akashvibhute 0:30537dec6e0b 22 goal()
akashvibhute 0:30537dec6e0b 23 {
akashvibhute 0:30537dec6e0b 24 }
akashvibhute 0:30537dec6e0b 25
akashvibhute 0:30537dec6e0b 26 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 27 {
akashvibhute 0:30537dec6e0b 28 int offset = 0;
akashvibhute 0:30537dec6e0b 29 offset += this->start.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 30 offset += this->goal.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 31 return offset;
akashvibhute 0:30537dec6e0b 32 }
akashvibhute 0:30537dec6e0b 33
akashvibhute 0:30537dec6e0b 34 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 35 {
akashvibhute 0:30537dec6e0b 36 int offset = 0;
akashvibhute 0:30537dec6e0b 37 offset += this->start.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 38 offset += this->goal.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 39 return offset;
akashvibhute 0:30537dec6e0b 40 }
akashvibhute 0:30537dec6e0b 41
akashvibhute 0:30537dec6e0b 42 const char * getType(){ return MAKENAVPLAN; };
akashvibhute 0:30537dec6e0b 43 const char * getMD5(){ return "2fe3126bd5b2d56edd5005220333d4fd"; };
akashvibhute 0:30537dec6e0b 44
akashvibhute 0:30537dec6e0b 45 };
akashvibhute 0:30537dec6e0b 46
akashvibhute 0:30537dec6e0b 47 class MakeNavPlanResponse : public ros::Msg
akashvibhute 0:30537dec6e0b 48 {
akashvibhute 0:30537dec6e0b 49 public:
akashvibhute 0:30537dec6e0b 50 uint8_t plan_found;
akashvibhute 0:30537dec6e0b 51 const char* error_message;
akashvibhute 0:30537dec6e0b 52 uint8_t path_length;
akashvibhute 0:30537dec6e0b 53 geometry_msgs::PoseStamped st_path;
akashvibhute 0:30537dec6e0b 54 geometry_msgs::PoseStamped * path;
akashvibhute 0:30537dec6e0b 55
akashvibhute 0:30537dec6e0b 56 MakeNavPlanResponse():
akashvibhute 0:30537dec6e0b 57 plan_found(0),
akashvibhute 0:30537dec6e0b 58 error_message(""),
akashvibhute 0:30537dec6e0b 59 path_length(0), path(NULL)
akashvibhute 0:30537dec6e0b 60 {
akashvibhute 0:30537dec6e0b 61 }
akashvibhute 0:30537dec6e0b 62
akashvibhute 0:30537dec6e0b 63 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 64 {
akashvibhute 0:30537dec6e0b 65 int offset = 0;
akashvibhute 0:30537dec6e0b 66 *(outbuffer + offset + 0) = (this->plan_found >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 67 offset += sizeof(this->plan_found);
akashvibhute 0:30537dec6e0b 68 uint32_t length_error_message = strlen(this->error_message);
akashvibhute 0:30537dec6e0b 69 memcpy(outbuffer + offset, &length_error_message, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 70 offset += 4;
akashvibhute 0:30537dec6e0b 71 memcpy(outbuffer + offset, this->error_message, length_error_message);
akashvibhute 0:30537dec6e0b 72 offset += length_error_message;
akashvibhute 0:30537dec6e0b 73 *(outbuffer + offset++) = path_length;
akashvibhute 0:30537dec6e0b 74 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 75 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 76 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 77 for( uint8_t i = 0; i < path_length; i++){
akashvibhute 0:30537dec6e0b 78 offset += this->path[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 79 }
akashvibhute 0:30537dec6e0b 80 return offset;
akashvibhute 0:30537dec6e0b 81 }
akashvibhute 0:30537dec6e0b 82
akashvibhute 0:30537dec6e0b 83 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 84 {
akashvibhute 0:30537dec6e0b 85 int offset = 0;
akashvibhute 0:30537dec6e0b 86 this->plan_found = ((uint8_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 87 offset += sizeof(this->plan_found);
akashvibhute 0:30537dec6e0b 88 uint32_t length_error_message;
akashvibhute 0:30537dec6e0b 89 memcpy(&length_error_message, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 90 offset += 4;
akashvibhute 0:30537dec6e0b 91 for(unsigned int k= offset; k< offset+length_error_message; ++k){
akashvibhute 0:30537dec6e0b 92 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 93 }
akashvibhute 0:30537dec6e0b 94 inbuffer[offset+length_error_message-1]=0;
akashvibhute 0:30537dec6e0b 95 this->error_message = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 96 offset += length_error_message;
akashvibhute 0:30537dec6e0b 97 uint8_t path_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 98 if(path_lengthT > path_length)
akashvibhute 0:30537dec6e0b 99 this->path = (geometry_msgs::PoseStamped*)realloc(this->path, path_lengthT * sizeof(geometry_msgs::PoseStamped));
akashvibhute 0:30537dec6e0b 100 offset += 3;
akashvibhute 0:30537dec6e0b 101 path_length = path_lengthT;
akashvibhute 0:30537dec6e0b 102 for( uint8_t i = 0; i < path_length; i++){
akashvibhute 0:30537dec6e0b 103 offset += this->st_path.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 104 memcpy( &(this->path[i]), &(this->st_path), sizeof(geometry_msgs::PoseStamped));
akashvibhute 0:30537dec6e0b 105 }
akashvibhute 0:30537dec6e0b 106 return offset;
akashvibhute 0:30537dec6e0b 107 }
akashvibhute 0:30537dec6e0b 108
akashvibhute 0:30537dec6e0b 109 const char * getType(){ return MAKENAVPLAN; };
akashvibhute 0:30537dec6e0b 110 const char * getMD5(){ return "8b8ed7edf1b237dc9ddda8c8ffed5d3a"; };
akashvibhute 0:30537dec6e0b 111
akashvibhute 0:30537dec6e0b 112 };
akashvibhute 0:30537dec6e0b 113
akashvibhute 0:30537dec6e0b 114 class MakeNavPlan {
akashvibhute 0:30537dec6e0b 115 public:
akashvibhute 0:30537dec6e0b 116 typedef MakeNavPlanRequest Request;
akashvibhute 0:30537dec6e0b 117 typedef MakeNavPlanResponse Response;
akashvibhute 0:30537dec6e0b 118 };
akashvibhute 0:30537dec6e0b 119
akashvibhute 0:30537dec6e0b 120 }
akashvibhute 0:30537dec6e0b 121 #endif
akashvibhute 0:30537dec6e0b 122