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_manipulation_msgs_Grasp_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_manipulation_msgs_Grasp_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 "sensor_msgs/JointState.h"
akashvibhute 0:30537dec6e0b 9 #include "geometry_msgs/PoseStamped.h"
akashvibhute 0:30537dec6e0b 10 #include "manipulation_msgs/GripperTranslation.h"
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 namespace manipulation_msgs
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 class Grasp : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 const char* id;
akashvibhute 0:30537dec6e0b 19 sensor_msgs::JointState pre_grasp_posture;
akashvibhute 0:30537dec6e0b 20 sensor_msgs::JointState grasp_posture;
akashvibhute 0:30537dec6e0b 21 geometry_msgs::PoseStamped grasp_pose;
akashvibhute 0:30537dec6e0b 22 float grasp_quality;
akashvibhute 0:30537dec6e0b 23 manipulation_msgs::GripperTranslation approach;
akashvibhute 0:30537dec6e0b 24 manipulation_msgs::GripperTranslation retreat;
akashvibhute 0:30537dec6e0b 25 float max_contact_force;
akashvibhute 0:30537dec6e0b 26 uint8_t allowed_touch_objects_length;
akashvibhute 0:30537dec6e0b 27 char* st_allowed_touch_objects;
akashvibhute 0:30537dec6e0b 28 char* * allowed_touch_objects;
akashvibhute 0:30537dec6e0b 29
akashvibhute 0:30537dec6e0b 30 Grasp():
akashvibhute 0:30537dec6e0b 31 id(""),
akashvibhute 0:30537dec6e0b 32 pre_grasp_posture(),
akashvibhute 0:30537dec6e0b 33 grasp_posture(),
akashvibhute 0:30537dec6e0b 34 grasp_pose(),
akashvibhute 0:30537dec6e0b 35 grasp_quality(0),
akashvibhute 0:30537dec6e0b 36 approach(),
akashvibhute 0:30537dec6e0b 37 retreat(),
akashvibhute 0:30537dec6e0b 38 max_contact_force(0),
akashvibhute 0:30537dec6e0b 39 allowed_touch_objects_length(0), allowed_touch_objects(NULL)
akashvibhute 0:30537dec6e0b 40 {
akashvibhute 0:30537dec6e0b 41 }
akashvibhute 0:30537dec6e0b 42
akashvibhute 0:30537dec6e0b 43 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 44 {
akashvibhute 0:30537dec6e0b 45 int offset = 0;
akashvibhute 0:30537dec6e0b 46 uint32_t length_id = strlen(this->id);
akashvibhute 0:30537dec6e0b 47 memcpy(outbuffer + offset, &length_id, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 48 offset += 4;
akashvibhute 0:30537dec6e0b 49 memcpy(outbuffer + offset, this->id, length_id);
akashvibhute 0:30537dec6e0b 50 offset += length_id;
akashvibhute 0:30537dec6e0b 51 offset += this->pre_grasp_posture.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 52 offset += this->grasp_posture.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 53 offset += this->grasp_pose.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 54 offset += serializeAvrFloat64(outbuffer + offset, this->grasp_quality);
akashvibhute 0:30537dec6e0b 55 offset += this->approach.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 56 offset += this->retreat.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 57 union {
akashvibhute 0:30537dec6e0b 58 float real;
akashvibhute 0:30537dec6e0b 59 uint32_t base;
akashvibhute 0:30537dec6e0b 60 } u_max_contact_force;
akashvibhute 0:30537dec6e0b 61 u_max_contact_force.real = this->max_contact_force;
akashvibhute 0:30537dec6e0b 62 *(outbuffer + offset + 0) = (u_max_contact_force.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 63 *(outbuffer + offset + 1) = (u_max_contact_force.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 64 *(outbuffer + offset + 2) = (u_max_contact_force.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 65 *(outbuffer + offset + 3) = (u_max_contact_force.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 66 offset += sizeof(this->max_contact_force);
akashvibhute 0:30537dec6e0b 67 *(outbuffer + offset++) = allowed_touch_objects_length;
akashvibhute 0:30537dec6e0b 68 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 69 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 70 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 71 for( uint8_t i = 0; i < allowed_touch_objects_length; i++){
akashvibhute 0:30537dec6e0b 72 uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]);
akashvibhute 0:30537dec6e0b 73 memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 74 offset += 4;
akashvibhute 0:30537dec6e0b 75 memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi);
akashvibhute 0:30537dec6e0b 76 offset += length_allowed_touch_objectsi;
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 uint32_t length_id;
akashvibhute 0:30537dec6e0b 85 memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 86 offset += 4;
akashvibhute 0:30537dec6e0b 87 for(unsigned int k= offset; k< offset+length_id; ++k){
akashvibhute 0:30537dec6e0b 88 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 89 }
akashvibhute 0:30537dec6e0b 90 inbuffer[offset+length_id-1]=0;
akashvibhute 0:30537dec6e0b 91 this->id = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 92 offset += length_id;
akashvibhute 0:30537dec6e0b 93 offset += this->pre_grasp_posture.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 94 offset += this->grasp_posture.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 95 offset += this->grasp_pose.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 96 offset += deserializeAvrFloat64(inbuffer + offset, &(this->grasp_quality));
akashvibhute 0:30537dec6e0b 97 offset += this->approach.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 98 offset += this->retreat.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 99 union {
akashvibhute 0:30537dec6e0b 100 float real;
akashvibhute 0:30537dec6e0b 101 uint32_t base;
akashvibhute 0:30537dec6e0b 102 } u_max_contact_force;
akashvibhute 0:30537dec6e0b 103 u_max_contact_force.base = 0;
akashvibhute 0:30537dec6e0b 104 u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 105 u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 106 u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 107 u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 108 this->max_contact_force = u_max_contact_force.real;
akashvibhute 0:30537dec6e0b 109 offset += sizeof(this->max_contact_force);
akashvibhute 0:30537dec6e0b 110 uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 111 if(allowed_touch_objects_lengthT > allowed_touch_objects_length)
akashvibhute 0:30537dec6e0b 112 this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 113 offset += 3;
akashvibhute 0:30537dec6e0b 114 allowed_touch_objects_length = allowed_touch_objects_lengthT;
akashvibhute 0:30537dec6e0b 115 for( uint8_t i = 0; i < allowed_touch_objects_length; i++){
akashvibhute 0:30537dec6e0b 116 uint32_t length_st_allowed_touch_objects;
akashvibhute 0:30537dec6e0b 117 memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 118 offset += 4;
akashvibhute 0:30537dec6e0b 119 for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){
akashvibhute 0:30537dec6e0b 120 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 121 }
akashvibhute 0:30537dec6e0b 122 inbuffer[offset+length_st_allowed_touch_objects-1]=0;
akashvibhute 0:30537dec6e0b 123 this->st_allowed_touch_objects = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 124 offset += length_st_allowed_touch_objects;
akashvibhute 0:30537dec6e0b 125 memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*));
akashvibhute 0:30537dec6e0b 126 }
akashvibhute 0:30537dec6e0b 127 return offset;
akashvibhute 0:30537dec6e0b 128 }
akashvibhute 0:30537dec6e0b 129
akashvibhute 0:30537dec6e0b 130 const char * getType(){ return "manipulation_msgs/Grasp"; };
akashvibhute 0:30537dec6e0b 131 const char * getMD5(){ return "83bd11da422ea1917259ee456c0e315a"; };
akashvibhute 0:30537dec6e0b 132
akashvibhute 0:30537dec6e0b 133 };
akashvibhute 0:30537dec6e0b 134
akashvibhute 0:30537dec6e0b 135 }
akashvibhute 0:30537dec6e0b 136 #endif