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_MotionPlanDetailedResponse_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_moveit_msgs_MotionPlanDetailedResponse_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/RobotState.h"
akashvibhute 0:30537dec6e0b 9 #include "moveit_msgs/RobotTrajectory.h"
akashvibhute 0:30537dec6e0b 10 #include "moveit_msgs/MoveItErrorCodes.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 MotionPlanDetailedResponse : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 moveit_msgs::RobotState trajectory_start;
akashvibhute 0:30537dec6e0b 19 const char* group_name;
akashvibhute 0:30537dec6e0b 20 uint8_t trajectory_length;
akashvibhute 0:30537dec6e0b 21 moveit_msgs::RobotTrajectory st_trajectory;
akashvibhute 0:30537dec6e0b 22 moveit_msgs::RobotTrajectory * trajectory;
akashvibhute 0:30537dec6e0b 23 uint8_t description_length;
akashvibhute 0:30537dec6e0b 24 char* st_description;
akashvibhute 0:30537dec6e0b 25 char* * description;
akashvibhute 0:30537dec6e0b 26 uint8_t processing_time_length;
akashvibhute 0:30537dec6e0b 27 float st_processing_time;
akashvibhute 0:30537dec6e0b 28 float * processing_time;
akashvibhute 0:30537dec6e0b 29 moveit_msgs::MoveItErrorCodes error_code;
akashvibhute 0:30537dec6e0b 30
akashvibhute 0:30537dec6e0b 31 MotionPlanDetailedResponse():
akashvibhute 0:30537dec6e0b 32 trajectory_start(),
akashvibhute 0:30537dec6e0b 33 group_name(""),
akashvibhute 0:30537dec6e0b 34 trajectory_length(0), trajectory(NULL),
akashvibhute 0:30537dec6e0b 35 description_length(0), description(NULL),
akashvibhute 0:30537dec6e0b 36 processing_time_length(0), processing_time(NULL),
akashvibhute 0:30537dec6e0b 37 error_code()
akashvibhute 0:30537dec6e0b 38 {
akashvibhute 0:30537dec6e0b 39 }
akashvibhute 0:30537dec6e0b 40
akashvibhute 0:30537dec6e0b 41 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 42 {
akashvibhute 0:30537dec6e0b 43 int offset = 0;
akashvibhute 0:30537dec6e0b 44 offset += this->trajectory_start.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 45 uint32_t length_group_name = strlen(this->group_name);
akashvibhute 0:30537dec6e0b 46 memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 47 offset += 4;
akashvibhute 0:30537dec6e0b 48 memcpy(outbuffer + offset, this->group_name, length_group_name);
akashvibhute 0:30537dec6e0b 49 offset += length_group_name;
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset++) = trajectory_length;
akashvibhute 0:30537dec6e0b 51 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 53 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 54 for( uint8_t i = 0; i < trajectory_length; i++){
akashvibhute 0:30537dec6e0b 55 offset += this->trajectory[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 56 }
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset++) = description_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 < description_length; i++){
akashvibhute 0:30537dec6e0b 62 uint32_t length_descriptioni = strlen(this->description[i]);
akashvibhute 0:30537dec6e0b 63 memcpy(outbuffer + offset, &length_descriptioni, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 64 offset += 4;
akashvibhute 0:30537dec6e0b 65 memcpy(outbuffer + offset, this->description[i], length_descriptioni);
akashvibhute 0:30537dec6e0b 66 offset += length_descriptioni;
akashvibhute 0:30537dec6e0b 67 }
akashvibhute 0:30537dec6e0b 68 *(outbuffer + offset++) = processing_time_length;
akashvibhute 0:30537dec6e0b 69 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 70 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 71 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 72 for( uint8_t i = 0; i < processing_time_length; i++){
akashvibhute 0:30537dec6e0b 73 offset += serializeAvrFloat64(outbuffer + offset, this->processing_time[i]);
akashvibhute 0:30537dec6e0b 74 }
akashvibhute 0:30537dec6e0b 75 offset += this->error_code.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 76 return offset;
akashvibhute 0:30537dec6e0b 77 }
akashvibhute 0:30537dec6e0b 78
akashvibhute 0:30537dec6e0b 79 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 80 {
akashvibhute 0:30537dec6e0b 81 int offset = 0;
akashvibhute 0:30537dec6e0b 82 offset += this->trajectory_start.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 83 uint32_t length_group_name;
akashvibhute 0:30537dec6e0b 84 memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 85 offset += 4;
akashvibhute 0:30537dec6e0b 86 for(unsigned int k= offset; k< offset+length_group_name; ++k){
akashvibhute 0:30537dec6e0b 87 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 88 }
akashvibhute 0:30537dec6e0b 89 inbuffer[offset+length_group_name-1]=0;
akashvibhute 0:30537dec6e0b 90 this->group_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 91 offset += length_group_name;
akashvibhute 0:30537dec6e0b 92 uint8_t trajectory_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 93 if(trajectory_lengthT > trajectory_length)
akashvibhute 0:30537dec6e0b 94 this->trajectory = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory, trajectory_lengthT * sizeof(moveit_msgs::RobotTrajectory));
akashvibhute 0:30537dec6e0b 95 offset += 3;
akashvibhute 0:30537dec6e0b 96 trajectory_length = trajectory_lengthT;
akashvibhute 0:30537dec6e0b 97 for( uint8_t i = 0; i < trajectory_length; i++){
akashvibhute 0:30537dec6e0b 98 offset += this->st_trajectory.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 99 memcpy( &(this->trajectory[i]), &(this->st_trajectory), sizeof(moveit_msgs::RobotTrajectory));
akashvibhute 0:30537dec6e0b 100 }
akashvibhute 0:30537dec6e0b 101 uint8_t description_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 102 if(description_lengthT > description_length)
akashvibhute 0:30537dec6e0b 103 this->description = (char**)realloc(this->description, description_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 104 offset += 3;
akashvibhute 0:30537dec6e0b 105 description_length = description_lengthT;
akashvibhute 0:30537dec6e0b 106 for( uint8_t i = 0; i < description_length; i++){
akashvibhute 0:30537dec6e0b 107 uint32_t length_st_description;
akashvibhute 0:30537dec6e0b 108 memcpy(&length_st_description, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 109 offset += 4;
akashvibhute 0:30537dec6e0b 110 for(unsigned int k= offset; k< offset+length_st_description; ++k){
akashvibhute 0:30537dec6e0b 111 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 112 }
akashvibhute 0:30537dec6e0b 113 inbuffer[offset+length_st_description-1]=0;
akashvibhute 0:30537dec6e0b 114 this->st_description = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 115 offset += length_st_description;
akashvibhute 0:30537dec6e0b 116 memcpy( &(this->description[i]), &(this->st_description), sizeof(char*));
akashvibhute 0:30537dec6e0b 117 }
akashvibhute 0:30537dec6e0b 118 uint8_t processing_time_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 119 if(processing_time_lengthT > processing_time_length)
akashvibhute 0:30537dec6e0b 120 this->processing_time = (float*)realloc(this->processing_time, processing_time_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 121 offset += 3;
akashvibhute 0:30537dec6e0b 122 processing_time_length = processing_time_lengthT;
akashvibhute 0:30537dec6e0b 123 for( uint8_t i = 0; i < processing_time_length; i++){
akashvibhute 0:30537dec6e0b 124 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_processing_time));
akashvibhute 0:30537dec6e0b 125 memcpy( &(this->processing_time[i]), &(this->st_processing_time), sizeof(float));
akashvibhute 0:30537dec6e0b 126 }
akashvibhute 0:30537dec6e0b 127 offset += this->error_code.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 128 return offset;
akashvibhute 0:30537dec6e0b 129 }
akashvibhute 0:30537dec6e0b 130
akashvibhute 0:30537dec6e0b 131 const char * getType(){ return "moveit_msgs/MotionPlanDetailedResponse"; };
akashvibhute 0:30537dec6e0b 132 const char * getMD5(){ return "7b84c374bb2e37bdc0eba664f7636a8f"; };
akashvibhute 0:30537dec6e0b 133
akashvibhute 0:30537dec6e0b 134 };
akashvibhute 0:30537dec6e0b 135
akashvibhute 0:30537dec6e0b 136 }
akashvibhute 0:30537dec6e0b 137 #endif