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_PickupResult_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_moveit_msgs_PickupResult_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/MoveItErrorCodes.h"
akashvibhute 0:30537dec6e0b 9 #include "moveit_msgs/RobotState.h"
akashvibhute 0:30537dec6e0b 10 #include "moveit_msgs/RobotTrajectory.h"
akashvibhute 0:30537dec6e0b 11 #include "moveit_msgs/Grasp.h"
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 namespace moveit_msgs
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15
akashvibhute 0:30537dec6e0b 16 class PickupResult : public ros::Msg
akashvibhute 0:30537dec6e0b 17 {
akashvibhute 0:30537dec6e0b 18 public:
akashvibhute 0:30537dec6e0b 19 moveit_msgs::MoveItErrorCodes error_code;
akashvibhute 0:30537dec6e0b 20 moveit_msgs::RobotState trajectory_start;
akashvibhute 0:30537dec6e0b 21 uint8_t trajectory_stages_length;
akashvibhute 0:30537dec6e0b 22 moveit_msgs::RobotTrajectory st_trajectory_stages;
akashvibhute 0:30537dec6e0b 23 moveit_msgs::RobotTrajectory * trajectory_stages;
akashvibhute 0:30537dec6e0b 24 uint8_t trajectory_descriptions_length;
akashvibhute 0:30537dec6e0b 25 char* st_trajectory_descriptions;
akashvibhute 0:30537dec6e0b 26 char* * trajectory_descriptions;
akashvibhute 0:30537dec6e0b 27 moveit_msgs::Grasp grasp;
akashvibhute 0:30537dec6e0b 28
akashvibhute 0:30537dec6e0b 29 PickupResult():
akashvibhute 0:30537dec6e0b 30 error_code(),
akashvibhute 0:30537dec6e0b 31 trajectory_start(),
akashvibhute 0:30537dec6e0b 32 trajectory_stages_length(0), trajectory_stages(NULL),
akashvibhute 0:30537dec6e0b 33 trajectory_descriptions_length(0), trajectory_descriptions(NULL),
akashvibhute 0:30537dec6e0b 34 grasp()
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 offset += this->error_code.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 42 offset += this->trajectory_start.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 43 *(outbuffer + offset++) = trajectory_stages_length;
akashvibhute 0:30537dec6e0b 44 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 45 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 46 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 47 for( uint8_t i = 0; i < trajectory_stages_length; i++){
akashvibhute 0:30537dec6e0b 48 offset += this->trajectory_stages[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 49 }
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset++) = trajectory_descriptions_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_descriptions_length; i++){
akashvibhute 0:30537dec6e0b 55 uint32_t length_trajectory_descriptionsi = strlen(this->trajectory_descriptions[i]);
akashvibhute 0:30537dec6e0b 56 memcpy(outbuffer + offset, &length_trajectory_descriptionsi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 57 offset += 4;
akashvibhute 0:30537dec6e0b 58 memcpy(outbuffer + offset, this->trajectory_descriptions[i], length_trajectory_descriptionsi);
akashvibhute 0:30537dec6e0b 59 offset += length_trajectory_descriptionsi;
akashvibhute 0:30537dec6e0b 60 }
akashvibhute 0:30537dec6e0b 61 offset += this->grasp.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 62 return offset;
akashvibhute 0:30537dec6e0b 63 }
akashvibhute 0:30537dec6e0b 64
akashvibhute 0:30537dec6e0b 65 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 66 {
akashvibhute 0:30537dec6e0b 67 int offset = 0;
akashvibhute 0:30537dec6e0b 68 offset += this->error_code.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 69 offset += this->trajectory_start.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 70 uint8_t trajectory_stages_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 71 if(trajectory_stages_lengthT > trajectory_stages_length)
akashvibhute 0:30537dec6e0b 72 this->trajectory_stages = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory_stages, trajectory_stages_lengthT * sizeof(moveit_msgs::RobotTrajectory));
akashvibhute 0:30537dec6e0b 73 offset += 3;
akashvibhute 0:30537dec6e0b 74 trajectory_stages_length = trajectory_stages_lengthT;
akashvibhute 0:30537dec6e0b 75 for( uint8_t i = 0; i < trajectory_stages_length; i++){
akashvibhute 0:30537dec6e0b 76 offset += this->st_trajectory_stages.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 77 memcpy( &(this->trajectory_stages[i]), &(this->st_trajectory_stages), sizeof(moveit_msgs::RobotTrajectory));
akashvibhute 0:30537dec6e0b 78 }
akashvibhute 0:30537dec6e0b 79 uint8_t trajectory_descriptions_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 80 if(trajectory_descriptions_lengthT > trajectory_descriptions_length)
akashvibhute 0:30537dec6e0b 81 this->trajectory_descriptions = (char**)realloc(this->trajectory_descriptions, trajectory_descriptions_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 82 offset += 3;
akashvibhute 0:30537dec6e0b 83 trajectory_descriptions_length = trajectory_descriptions_lengthT;
akashvibhute 0:30537dec6e0b 84 for( uint8_t i = 0; i < trajectory_descriptions_length; i++){
akashvibhute 0:30537dec6e0b 85 uint32_t length_st_trajectory_descriptions;
akashvibhute 0:30537dec6e0b 86 memcpy(&length_st_trajectory_descriptions, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 87 offset += 4;
akashvibhute 0:30537dec6e0b 88 for(unsigned int k= offset; k< offset+length_st_trajectory_descriptions; ++k){
akashvibhute 0:30537dec6e0b 89 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 90 }
akashvibhute 0:30537dec6e0b 91 inbuffer[offset+length_st_trajectory_descriptions-1]=0;
akashvibhute 0:30537dec6e0b 92 this->st_trajectory_descriptions = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 93 offset += length_st_trajectory_descriptions;
akashvibhute 0:30537dec6e0b 94 memcpy( &(this->trajectory_descriptions[i]), &(this->st_trajectory_descriptions), sizeof(char*));
akashvibhute 0:30537dec6e0b 95 }
akashvibhute 0:30537dec6e0b 96 offset += this->grasp.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 97 return offset;
akashvibhute 0:30537dec6e0b 98 }
akashvibhute 0:30537dec6e0b 99
akashvibhute 0:30537dec6e0b 100 const char * getType(){ return "moveit_msgs/PickupResult"; };
akashvibhute 0:30537dec6e0b 101 const char * getMD5(){ return "23c6d8bf0580f4bc8f7a8e1f59b4b6b7"; };
akashvibhute 0:30537dec6e0b 102
akashvibhute 0:30537dec6e0b 103 };
akashvibhute 0:30537dec6e0b 104
akashvibhute 0:30537dec6e0b 105 }
akashvibhute 0:30537dec6e0b 106 #endif