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_QueryPlannerInterfaces_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_SERVICE_QueryPlannerInterfaces_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/PlannerInterfaceDescription.h"
akashvibhute 0:30537dec6e0b 8
akashvibhute 0:30537dec6e0b 9 namespace moveit_msgs
akashvibhute 0:30537dec6e0b 10 {
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 static const char QUERYPLANNERINTERFACES[] = "moveit_msgs/QueryPlannerInterfaces";
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 class QueryPlannerInterfacesRequest : public ros::Msg
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16 public:
akashvibhute 0:30537dec6e0b 17
akashvibhute 0:30537dec6e0b 18 QueryPlannerInterfacesRequest()
akashvibhute 0:30537dec6e0b 19 {
akashvibhute 0:30537dec6e0b 20 }
akashvibhute 0:30537dec6e0b 21
akashvibhute 0:30537dec6e0b 22 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 23 {
akashvibhute 0:30537dec6e0b 24 int offset = 0;
akashvibhute 0:30537dec6e0b 25 return offset;
akashvibhute 0:30537dec6e0b 26 }
akashvibhute 0:30537dec6e0b 27
akashvibhute 0:30537dec6e0b 28 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 29 {
akashvibhute 0:30537dec6e0b 30 int offset = 0;
akashvibhute 0:30537dec6e0b 31 return offset;
akashvibhute 0:30537dec6e0b 32 }
akashvibhute 0:30537dec6e0b 33
akashvibhute 0:30537dec6e0b 34 const char * getType(){ return QUERYPLANNERINTERFACES; };
akashvibhute 0:30537dec6e0b 35 const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
akashvibhute 0:30537dec6e0b 36
akashvibhute 0:30537dec6e0b 37 };
akashvibhute 0:30537dec6e0b 38
akashvibhute 0:30537dec6e0b 39 class QueryPlannerInterfacesResponse : public ros::Msg
akashvibhute 0:30537dec6e0b 40 {
akashvibhute 0:30537dec6e0b 41 public:
akashvibhute 0:30537dec6e0b 42 uint8_t planner_interfaces_length;
akashvibhute 0:30537dec6e0b 43 moveit_msgs::PlannerInterfaceDescription st_planner_interfaces;
akashvibhute 0:30537dec6e0b 44 moveit_msgs::PlannerInterfaceDescription * planner_interfaces;
akashvibhute 0:30537dec6e0b 45
akashvibhute 0:30537dec6e0b 46 QueryPlannerInterfacesResponse():
akashvibhute 0:30537dec6e0b 47 planner_interfaces_length(0), planner_interfaces(NULL)
akashvibhute 0:30537dec6e0b 48 {
akashvibhute 0:30537dec6e0b 49 }
akashvibhute 0:30537dec6e0b 50
akashvibhute 0:30537dec6e0b 51 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 52 {
akashvibhute 0:30537dec6e0b 53 int offset = 0;
akashvibhute 0:30537dec6e0b 54 *(outbuffer + offset++) = planner_interfaces_length;
akashvibhute 0:30537dec6e0b 55 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 56 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 58 for( uint8_t i = 0; i < planner_interfaces_length; i++){
akashvibhute 0:30537dec6e0b 59 offset += this->planner_interfaces[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 60 }
akashvibhute 0:30537dec6e0b 61 return offset;
akashvibhute 0:30537dec6e0b 62 }
akashvibhute 0:30537dec6e0b 63
akashvibhute 0:30537dec6e0b 64 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 65 {
akashvibhute 0:30537dec6e0b 66 int offset = 0;
akashvibhute 0:30537dec6e0b 67 uint8_t planner_interfaces_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 68 if(planner_interfaces_lengthT > planner_interfaces_length)
akashvibhute 0:30537dec6e0b 69 this->planner_interfaces = (moveit_msgs::PlannerInterfaceDescription*)realloc(this->planner_interfaces, planner_interfaces_lengthT * sizeof(moveit_msgs::PlannerInterfaceDescription));
akashvibhute 0:30537dec6e0b 70 offset += 3;
akashvibhute 0:30537dec6e0b 71 planner_interfaces_length = planner_interfaces_lengthT;
akashvibhute 0:30537dec6e0b 72 for( uint8_t i = 0; i < planner_interfaces_length; i++){
akashvibhute 0:30537dec6e0b 73 offset += this->st_planner_interfaces.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 74 memcpy( &(this->planner_interfaces[i]), &(this->st_planner_interfaces), sizeof(moveit_msgs::PlannerInterfaceDescription));
akashvibhute 0:30537dec6e0b 75 }
akashvibhute 0:30537dec6e0b 76 return offset;
akashvibhute 0:30537dec6e0b 77 }
akashvibhute 0:30537dec6e0b 78
akashvibhute 0:30537dec6e0b 79 const char * getType(){ return QUERYPLANNERINTERFACES; };
akashvibhute 0:30537dec6e0b 80 const char * getMD5(){ return "acd3317a4c5631f33127fb428209db05"; };
akashvibhute 0:30537dec6e0b 81
akashvibhute 0:30537dec6e0b 82 };
akashvibhute 0:30537dec6e0b 83
akashvibhute 0:30537dec6e0b 84 class QueryPlannerInterfaces {
akashvibhute 0:30537dec6e0b 85 public:
akashvibhute 0:30537dec6e0b 86 typedef QueryPlannerInterfacesRequest Request;
akashvibhute 0:30537dec6e0b 87 typedef QueryPlannerInterfacesResponse Response;
akashvibhute 0:30537dec6e0b 88 };
akashvibhute 0:30537dec6e0b 89
akashvibhute 0:30537dec6e0b 90 }
akashvibhute 0:30537dec6e0b 91 #endif
akashvibhute 0:30537dec6e0b 92