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_SERVICE_GetCartesianPath_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_SERVICE_GetCartesianPath_h
akashvibhute 0:30537dec6e0b 3 #include <stdint.h>
akashvibhute 0:30537dec6e0b 4 #include <string.h>
akashvibhute 0:30537dec6e0b 5 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 6 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 7 #include "std_msgs/Header.h"
akashvibhute 0:30537dec6e0b 8 #include "moveit_msgs/RobotTrajectory.h"
akashvibhute 0:30537dec6e0b 9 #include "moveit_msgs/RobotState.h"
akashvibhute 0:30537dec6e0b 10 #include "moveit_msgs/MoveItErrorCodes.h"
akashvibhute 0:30537dec6e0b 11 #include "geometry_msgs/Pose.h"
akashvibhute 0:30537dec6e0b 12 #include "moveit_msgs/Constraints.h"
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 namespace moveit_msgs
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16
akashvibhute 0:30537dec6e0b 17 static const char GETCARTESIANPATH[] = "moveit_msgs/GetCartesianPath";
akashvibhute 0:30537dec6e0b 18
akashvibhute 0:30537dec6e0b 19 class GetCartesianPathRequest : public ros::Msg
akashvibhute 0:30537dec6e0b 20 {
akashvibhute 0:30537dec6e0b 21 public:
akashvibhute 0:30537dec6e0b 22 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 23 moveit_msgs::RobotState start_state;
akashvibhute 0:30537dec6e0b 24 const char* group_name;
akashvibhute 0:30537dec6e0b 25 const char* link_name;
akashvibhute 0:30537dec6e0b 26 uint8_t waypoints_length;
akashvibhute 0:30537dec6e0b 27 geometry_msgs::Pose st_waypoints;
akashvibhute 0:30537dec6e0b 28 geometry_msgs::Pose * waypoints;
akashvibhute 0:30537dec6e0b 29 float max_step;
akashvibhute 0:30537dec6e0b 30 float jump_threshold;
akashvibhute 0:30537dec6e0b 31 bool avoid_collisions;
akashvibhute 0:30537dec6e0b 32 moveit_msgs::Constraints path_constraints;
akashvibhute 0:30537dec6e0b 33
akashvibhute 0:30537dec6e0b 34 GetCartesianPathRequest():
akashvibhute 0:30537dec6e0b 35 header(),
akashvibhute 0:30537dec6e0b 36 start_state(),
akashvibhute 0:30537dec6e0b 37 group_name(""),
akashvibhute 0:30537dec6e0b 38 link_name(""),
akashvibhute 0:30537dec6e0b 39 waypoints_length(0), waypoints(NULL),
akashvibhute 0:30537dec6e0b 40 max_step(0),
akashvibhute 0:30537dec6e0b 41 jump_threshold(0),
akashvibhute 0:30537dec6e0b 42 avoid_collisions(0),
akashvibhute 0:30537dec6e0b 43 path_constraints()
akashvibhute 0:30537dec6e0b 44 {
akashvibhute 0:30537dec6e0b 45 }
akashvibhute 0:30537dec6e0b 46
akashvibhute 0:30537dec6e0b 47 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 48 {
akashvibhute 0:30537dec6e0b 49 int offset = 0;
akashvibhute 0:30537dec6e0b 50 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 51 offset += this->start_state.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 52 uint32_t length_group_name = strlen(this->group_name);
akashvibhute 0:30537dec6e0b 53 memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 54 offset += 4;
akashvibhute 0:30537dec6e0b 55 memcpy(outbuffer + offset, this->group_name, length_group_name);
akashvibhute 0:30537dec6e0b 56 offset += length_group_name;
akashvibhute 0:30537dec6e0b 57 uint32_t length_link_name = strlen(this->link_name);
akashvibhute 0:30537dec6e0b 58 memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 59 offset += 4;
akashvibhute 0:30537dec6e0b 60 memcpy(outbuffer + offset, this->link_name, length_link_name);
akashvibhute 0:30537dec6e0b 61 offset += length_link_name;
akashvibhute 0:30537dec6e0b 62 *(outbuffer + offset++) = waypoints_length;
akashvibhute 0:30537dec6e0b 63 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 64 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 65 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 66 for( uint8_t i = 0; i < waypoints_length; i++){
akashvibhute 0:30537dec6e0b 67 offset += this->waypoints[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 68 }
akashvibhute 0:30537dec6e0b 69 offset += serializeAvrFloat64(outbuffer + offset, this->max_step);
akashvibhute 0:30537dec6e0b 70 offset += serializeAvrFloat64(outbuffer + offset, this->jump_threshold);
akashvibhute 0:30537dec6e0b 71 union {
akashvibhute 0:30537dec6e0b 72 bool real;
akashvibhute 0:30537dec6e0b 73 uint8_t base;
akashvibhute 0:30537dec6e0b 74 } u_avoid_collisions;
akashvibhute 0:30537dec6e0b 75 u_avoid_collisions.real = this->avoid_collisions;
akashvibhute 0:30537dec6e0b 76 *(outbuffer + offset + 0) = (u_avoid_collisions.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 77 offset += sizeof(this->avoid_collisions);
akashvibhute 0:30537dec6e0b 78 offset += this->path_constraints.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 79 return offset;
akashvibhute 0:30537dec6e0b 80 }
akashvibhute 0:30537dec6e0b 81
akashvibhute 0:30537dec6e0b 82 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 83 {
akashvibhute 0:30537dec6e0b 84 int offset = 0;
akashvibhute 0:30537dec6e0b 85 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 86 offset += this->start_state.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 87 uint32_t length_group_name;
akashvibhute 0:30537dec6e0b 88 memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 89 offset += 4;
akashvibhute 0:30537dec6e0b 90 for(unsigned int k= offset; k< offset+length_group_name; ++k){
akashvibhute 0:30537dec6e0b 91 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 92 }
akashvibhute 0:30537dec6e0b 93 inbuffer[offset+length_group_name-1]=0;
akashvibhute 0:30537dec6e0b 94 this->group_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 95 offset += length_group_name;
akashvibhute 0:30537dec6e0b 96 uint32_t length_link_name;
akashvibhute 0:30537dec6e0b 97 memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 98 offset += 4;
akashvibhute 0:30537dec6e0b 99 for(unsigned int k= offset; k< offset+length_link_name; ++k){
akashvibhute 0:30537dec6e0b 100 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 101 }
akashvibhute 0:30537dec6e0b 102 inbuffer[offset+length_link_name-1]=0;
akashvibhute 0:30537dec6e0b 103 this->link_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 104 offset += length_link_name;
akashvibhute 0:30537dec6e0b 105 uint8_t waypoints_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 106 if(waypoints_lengthT > waypoints_length)
akashvibhute 0:30537dec6e0b 107 this->waypoints = (geometry_msgs::Pose*)realloc(this->waypoints, waypoints_lengthT * sizeof(geometry_msgs::Pose));
akashvibhute 0:30537dec6e0b 108 offset += 3;
akashvibhute 0:30537dec6e0b 109 waypoints_length = waypoints_lengthT;
akashvibhute 0:30537dec6e0b 110 for( uint8_t i = 0; i < waypoints_length; i++){
akashvibhute 0:30537dec6e0b 111 offset += this->st_waypoints.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 112 memcpy( &(this->waypoints[i]), &(this->st_waypoints), sizeof(geometry_msgs::Pose));
akashvibhute 0:30537dec6e0b 113 }
akashvibhute 0:30537dec6e0b 114 offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_step));
akashvibhute 0:30537dec6e0b 115 offset += deserializeAvrFloat64(inbuffer + offset, &(this->jump_threshold));
akashvibhute 0:30537dec6e0b 116 union {
akashvibhute 0:30537dec6e0b 117 bool real;
akashvibhute 0:30537dec6e0b 118 uint8_t base;
akashvibhute 0:30537dec6e0b 119 } u_avoid_collisions;
akashvibhute 0:30537dec6e0b 120 u_avoid_collisions.base = 0;
akashvibhute 0:30537dec6e0b 121 u_avoid_collisions.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 122 this->avoid_collisions = u_avoid_collisions.real;
akashvibhute 0:30537dec6e0b 123 offset += sizeof(this->avoid_collisions);
akashvibhute 0:30537dec6e0b 124 offset += this->path_constraints.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 125 return offset;
akashvibhute 0:30537dec6e0b 126 }
akashvibhute 0:30537dec6e0b 127
akashvibhute 0:30537dec6e0b 128 const char * getType(){ return GETCARTESIANPATH; };
akashvibhute 0:30537dec6e0b 129 const char * getMD5(){ return "b37c16ad7ed838d811a270a8054276b6"; };
akashvibhute 0:30537dec6e0b 130
akashvibhute 0:30537dec6e0b 131 };
akashvibhute 0:30537dec6e0b 132
akashvibhute 0:30537dec6e0b 133 class GetCartesianPathResponse : public ros::Msg
akashvibhute 0:30537dec6e0b 134 {
akashvibhute 0:30537dec6e0b 135 public:
akashvibhute 0:30537dec6e0b 136 moveit_msgs::RobotState start_state;
akashvibhute 0:30537dec6e0b 137 moveit_msgs::RobotTrajectory solution;
akashvibhute 0:30537dec6e0b 138 float fraction;
akashvibhute 0:30537dec6e0b 139 moveit_msgs::MoveItErrorCodes error_code;
akashvibhute 0:30537dec6e0b 140
akashvibhute 0:30537dec6e0b 141 GetCartesianPathResponse():
akashvibhute 0:30537dec6e0b 142 start_state(),
akashvibhute 0:30537dec6e0b 143 solution(),
akashvibhute 0:30537dec6e0b 144 fraction(0),
akashvibhute 0:30537dec6e0b 145 error_code()
akashvibhute 0:30537dec6e0b 146 {
akashvibhute 0:30537dec6e0b 147 }
akashvibhute 0:30537dec6e0b 148
akashvibhute 0:30537dec6e0b 149 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 150 {
akashvibhute 0:30537dec6e0b 151 int offset = 0;
akashvibhute 0:30537dec6e0b 152 offset += this->start_state.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 153 offset += this->solution.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 154 offset += serializeAvrFloat64(outbuffer + offset, this->fraction);
akashvibhute 0:30537dec6e0b 155 offset += this->error_code.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 156 return offset;
akashvibhute 0:30537dec6e0b 157 }
akashvibhute 0:30537dec6e0b 158
akashvibhute 0:30537dec6e0b 159 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 160 {
akashvibhute 0:30537dec6e0b 161 int offset = 0;
akashvibhute 0:30537dec6e0b 162 offset += this->start_state.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 163 offset += this->solution.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 164 offset += deserializeAvrFloat64(inbuffer + offset, &(this->fraction));
akashvibhute 0:30537dec6e0b 165 offset += this->error_code.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 166 return offset;
akashvibhute 0:30537dec6e0b 167 }
akashvibhute 0:30537dec6e0b 168
akashvibhute 0:30537dec6e0b 169 const char * getType(){ return GETCARTESIANPATH; };
akashvibhute 0:30537dec6e0b 170 const char * getMD5(){ return "45414110461a45eb0e273e013924ce59"; };
akashvibhute 0:30537dec6e0b 171
akashvibhute 0:30537dec6e0b 172 };
akashvibhute 0:30537dec6e0b 173
akashvibhute 0:30537dec6e0b 174 class GetCartesianPath {
akashvibhute 0:30537dec6e0b 175 public:
akashvibhute 0:30537dec6e0b 176 typedef GetCartesianPathRequest Request;
akashvibhute 0:30537dec6e0b 177 typedef GetCartesianPathResponse Response;
akashvibhute 0:30537dec6e0b 178 };
akashvibhute 0:30537dec6e0b 179
akashvibhute 0:30537dec6e0b 180 }
akashvibhute 0:30537dec6e0b 181 #endif
akashvibhute 0:30537dec6e0b 182