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