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_sensor_msgs_MultiDOFJointState_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_sensor_msgs_MultiDOFJointState_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 "std_msgs/Header.h"
akashvibhute 0:30537dec6e0b 9 #include "geometry_msgs/Transform.h"
akashvibhute 0:30537dec6e0b 10 #include "geometry_msgs/Twist.h"
akashvibhute 0:30537dec6e0b 11 #include "geometry_msgs/Wrench.h"
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 namespace sensor_msgs
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15
akashvibhute 0:30537dec6e0b 16 class MultiDOFJointState : public ros::Msg
akashvibhute 0:30537dec6e0b 17 {
akashvibhute 0:30537dec6e0b 18 public:
akashvibhute 0:30537dec6e0b 19 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 20 uint8_t joint_names_length;
akashvibhute 0:30537dec6e0b 21 char* st_joint_names;
akashvibhute 0:30537dec6e0b 22 char* * joint_names;
akashvibhute 0:30537dec6e0b 23 uint8_t transforms_length;
akashvibhute 0:30537dec6e0b 24 geometry_msgs::Transform st_transforms;
akashvibhute 0:30537dec6e0b 25 geometry_msgs::Transform * transforms;
akashvibhute 0:30537dec6e0b 26 uint8_t twist_length;
akashvibhute 0:30537dec6e0b 27 geometry_msgs::Twist st_twist;
akashvibhute 0:30537dec6e0b 28 geometry_msgs::Twist * twist;
akashvibhute 0:30537dec6e0b 29 uint8_t wrench_length;
akashvibhute 0:30537dec6e0b 30 geometry_msgs::Wrench st_wrench;
akashvibhute 0:30537dec6e0b 31 geometry_msgs::Wrench * wrench;
akashvibhute 0:30537dec6e0b 32
akashvibhute 0:30537dec6e0b 33 MultiDOFJointState():
akashvibhute 0:30537dec6e0b 34 header(),
akashvibhute 0:30537dec6e0b 35 joint_names_length(0), joint_names(NULL),
akashvibhute 0:30537dec6e0b 36 transforms_length(0), transforms(NULL),
akashvibhute 0:30537dec6e0b 37 twist_length(0), twist(NULL),
akashvibhute 0:30537dec6e0b 38 wrench_length(0), wrench(NULL)
akashvibhute 0:30537dec6e0b 39 {
akashvibhute 0:30537dec6e0b 40 }
akashvibhute 0:30537dec6e0b 41
akashvibhute 0:30537dec6e0b 42 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 43 {
akashvibhute 0:30537dec6e0b 44 int offset = 0;
akashvibhute 0:30537dec6e0b 45 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 46 *(outbuffer + offset++) = joint_names_length;
akashvibhute 0:30537dec6e0b 47 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 48 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 50 for( uint8_t i = 0; i < joint_names_length; i++){
akashvibhute 0:30537dec6e0b 51 uint32_t length_joint_namesi = strlen(this->joint_names[i]);
akashvibhute 0:30537dec6e0b 52 memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 53 offset += 4;
akashvibhute 0:30537dec6e0b 54 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
akashvibhute 0:30537dec6e0b 55 offset += length_joint_namesi;
akashvibhute 0:30537dec6e0b 56 }
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset++) = transforms_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 < transforms_length; i++){
akashvibhute 0:30537dec6e0b 62 offset += this->transforms[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 63 }
akashvibhute 0:30537dec6e0b 64 *(outbuffer + offset++) = twist_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 < twist_length; i++){
akashvibhute 0:30537dec6e0b 69 offset += this->twist[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 70 }
akashvibhute 0:30537dec6e0b 71 *(outbuffer + offset++) = wrench_length;
akashvibhute 0:30537dec6e0b 72 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 73 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 74 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 75 for( uint8_t i = 0; i < wrench_length; i++){
akashvibhute 0:30537dec6e0b 76 offset += this->wrench[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 77 }
akashvibhute 0:30537dec6e0b 78 return offset;
akashvibhute 0:30537dec6e0b 79 }
akashvibhute 0:30537dec6e0b 80
akashvibhute 0:30537dec6e0b 81 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 82 {
akashvibhute 0:30537dec6e0b 83 int offset = 0;
akashvibhute 0:30537dec6e0b 84 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 85 uint8_t joint_names_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 86 if(joint_names_lengthT > joint_names_length)
akashvibhute 0:30537dec6e0b 87 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 88 offset += 3;
akashvibhute 0:30537dec6e0b 89 joint_names_length = joint_names_lengthT;
akashvibhute 0:30537dec6e0b 90 for( uint8_t i = 0; i < joint_names_length; i++){
akashvibhute 0:30537dec6e0b 91 uint32_t length_st_joint_names;
akashvibhute 0:30537dec6e0b 92 memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 93 offset += 4;
akashvibhute 0:30537dec6e0b 94 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
akashvibhute 0:30537dec6e0b 95 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 96 }
akashvibhute 0:30537dec6e0b 97 inbuffer[offset+length_st_joint_names-1]=0;
akashvibhute 0:30537dec6e0b 98 this->st_joint_names = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 99 offset += length_st_joint_names;
akashvibhute 0:30537dec6e0b 100 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
akashvibhute 0:30537dec6e0b 101 }
akashvibhute 0:30537dec6e0b 102 uint8_t transforms_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 103 if(transforms_lengthT > transforms_length)
akashvibhute 0:30537dec6e0b 104 this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
akashvibhute 0:30537dec6e0b 105 offset += 3;
akashvibhute 0:30537dec6e0b 106 transforms_length = transforms_lengthT;
akashvibhute 0:30537dec6e0b 107 for( uint8_t i = 0; i < transforms_length; i++){
akashvibhute 0:30537dec6e0b 108 offset += this->st_transforms.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 109 memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
akashvibhute 0:30537dec6e0b 110 }
akashvibhute 0:30537dec6e0b 111 uint8_t twist_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 112 if(twist_lengthT > twist_length)
akashvibhute 0:30537dec6e0b 113 this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
akashvibhute 0:30537dec6e0b 114 offset += 3;
akashvibhute 0:30537dec6e0b 115 twist_length = twist_lengthT;
akashvibhute 0:30537dec6e0b 116 for( uint8_t i = 0; i < twist_length; i++){
akashvibhute 0:30537dec6e0b 117 offset += this->st_twist.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 118 memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
akashvibhute 0:30537dec6e0b 119 }
akashvibhute 0:30537dec6e0b 120 uint8_t wrench_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 121 if(wrench_lengthT > wrench_length)
akashvibhute 0:30537dec6e0b 122 this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
akashvibhute 0:30537dec6e0b 123 offset += 3;
akashvibhute 0:30537dec6e0b 124 wrench_length = wrench_lengthT;
akashvibhute 0:30537dec6e0b 125 for( uint8_t i = 0; i < wrench_length; i++){
akashvibhute 0:30537dec6e0b 126 offset += this->st_wrench.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 127 memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench));
akashvibhute 0:30537dec6e0b 128 }
akashvibhute 0:30537dec6e0b 129 return offset;
akashvibhute 0:30537dec6e0b 130 }
akashvibhute 0:30537dec6e0b 131
akashvibhute 0:30537dec6e0b 132 const char * getType(){ return "sensor_msgs/MultiDOFJointState"; };
akashvibhute 0:30537dec6e0b 133 const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; };
akashvibhute 0:30537dec6e0b 134
akashvibhute 0:30537dec6e0b 135 };
akashvibhute 0:30537dec6e0b 136
akashvibhute 0:30537dec6e0b 137 }
akashvibhute 0:30537dec6e0b 138 #endif