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_MotionPlanRequest_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_moveit_msgs_MotionPlanRequest_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/WorkspaceParameters.h"
akashvibhute 0:30537dec6e0b 9 #include "moveit_msgs/RobotState.h"
akashvibhute 0:30537dec6e0b 10 #include "moveit_msgs/Constraints.h"
akashvibhute 0:30537dec6e0b 11 #include "moveit_msgs/TrajectoryConstraints.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 MotionPlanRequest : public ros::Msg
akashvibhute 0:30537dec6e0b 17 {
akashvibhute 0:30537dec6e0b 18 public:
akashvibhute 0:30537dec6e0b 19 moveit_msgs::WorkspaceParameters workspace_parameters;
akashvibhute 0:30537dec6e0b 20 moveit_msgs::RobotState start_state;
akashvibhute 0:30537dec6e0b 21 uint8_t goal_constraints_length;
akashvibhute 0:30537dec6e0b 22 moveit_msgs::Constraints st_goal_constraints;
akashvibhute 0:30537dec6e0b 23 moveit_msgs::Constraints * goal_constraints;
akashvibhute 0:30537dec6e0b 24 moveit_msgs::Constraints path_constraints;
akashvibhute 0:30537dec6e0b 25 moveit_msgs::TrajectoryConstraints trajectory_constraints;
akashvibhute 0:30537dec6e0b 26 const char* planner_id;
akashvibhute 0:30537dec6e0b 27 const char* group_name;
akashvibhute 0:30537dec6e0b 28 int32_t num_planning_attempts;
akashvibhute 0:30537dec6e0b 29 float allowed_planning_time;
akashvibhute 0:30537dec6e0b 30
akashvibhute 0:30537dec6e0b 31 MotionPlanRequest():
akashvibhute 0:30537dec6e0b 32 workspace_parameters(),
akashvibhute 0:30537dec6e0b 33 start_state(),
akashvibhute 0:30537dec6e0b 34 goal_constraints_length(0), goal_constraints(NULL),
akashvibhute 0:30537dec6e0b 35 path_constraints(),
akashvibhute 0:30537dec6e0b 36 trajectory_constraints(),
akashvibhute 0:30537dec6e0b 37 planner_id(""),
akashvibhute 0:30537dec6e0b 38 group_name(""),
akashvibhute 0:30537dec6e0b 39 num_planning_attempts(0),
akashvibhute 0:30537dec6e0b 40 allowed_planning_time(0)
akashvibhute 0:30537dec6e0b 41 {
akashvibhute 0:30537dec6e0b 42 }
akashvibhute 0:30537dec6e0b 43
akashvibhute 0:30537dec6e0b 44 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 45 {
akashvibhute 0:30537dec6e0b 46 int offset = 0;
akashvibhute 0:30537dec6e0b 47 offset += this->workspace_parameters.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 48 offset += this->start_state.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset++) = goal_constraints_length;
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 51 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 53 for( uint8_t i = 0; i < goal_constraints_length; i++){
akashvibhute 0:30537dec6e0b 54 offset += this->goal_constraints[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 55 }
akashvibhute 0:30537dec6e0b 56 offset += this->path_constraints.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 57 offset += this->trajectory_constraints.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 58 uint32_t length_planner_id = strlen(this->planner_id);
akashvibhute 0:30537dec6e0b 59 memcpy(outbuffer + offset, &length_planner_id, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 60 offset += 4;
akashvibhute 0:30537dec6e0b 61 memcpy(outbuffer + offset, this->planner_id, length_planner_id);
akashvibhute 0:30537dec6e0b 62 offset += length_planner_id;
akashvibhute 0:30537dec6e0b 63 uint32_t length_group_name = strlen(this->group_name);
akashvibhute 0:30537dec6e0b 64 memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 65 offset += 4;
akashvibhute 0:30537dec6e0b 66 memcpy(outbuffer + offset, this->group_name, length_group_name);
akashvibhute 0:30537dec6e0b 67 offset += length_group_name;
akashvibhute 0:30537dec6e0b 68 union {
akashvibhute 0:30537dec6e0b 69 int32_t real;
akashvibhute 0:30537dec6e0b 70 uint32_t base;
akashvibhute 0:30537dec6e0b 71 } u_num_planning_attempts;
akashvibhute 0:30537dec6e0b 72 u_num_planning_attempts.real = this->num_planning_attempts;
akashvibhute 0:30537dec6e0b 73 *(outbuffer + offset + 0) = (u_num_planning_attempts.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 74 *(outbuffer + offset + 1) = (u_num_planning_attempts.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 75 *(outbuffer + offset + 2) = (u_num_planning_attempts.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 76 *(outbuffer + offset + 3) = (u_num_planning_attempts.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 77 offset += sizeof(this->num_planning_attempts);
akashvibhute 0:30537dec6e0b 78 offset += serializeAvrFloat64(outbuffer + offset, this->allowed_planning_time);
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->workspace_parameters.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 86 offset += this->start_state.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 87 uint8_t goal_constraints_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 88 if(goal_constraints_lengthT > goal_constraints_length)
akashvibhute 0:30537dec6e0b 89 this->goal_constraints = (moveit_msgs::Constraints*)realloc(this->goal_constraints, goal_constraints_lengthT * sizeof(moveit_msgs::Constraints));
akashvibhute 0:30537dec6e0b 90 offset += 3;
akashvibhute 0:30537dec6e0b 91 goal_constraints_length = goal_constraints_lengthT;
akashvibhute 0:30537dec6e0b 92 for( uint8_t i = 0; i < goal_constraints_length; i++){
akashvibhute 0:30537dec6e0b 93 offset += this->st_goal_constraints.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 94 memcpy( &(this->goal_constraints[i]), &(this->st_goal_constraints), sizeof(moveit_msgs::Constraints));
akashvibhute 0:30537dec6e0b 95 }
akashvibhute 0:30537dec6e0b 96 offset += this->path_constraints.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 97 offset += this->trajectory_constraints.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 98 uint32_t length_planner_id;
akashvibhute 0:30537dec6e0b 99 memcpy(&length_planner_id, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 100 offset += 4;
akashvibhute 0:30537dec6e0b 101 for(unsigned int k= offset; k< offset+length_planner_id; ++k){
akashvibhute 0:30537dec6e0b 102 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 103 }
akashvibhute 0:30537dec6e0b 104 inbuffer[offset+length_planner_id-1]=0;
akashvibhute 0:30537dec6e0b 105 this->planner_id = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 106 offset += length_planner_id;
akashvibhute 0:30537dec6e0b 107 uint32_t length_group_name;
akashvibhute 0:30537dec6e0b 108 memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 109 offset += 4;
akashvibhute 0:30537dec6e0b 110 for(unsigned int k= offset; k< offset+length_group_name; ++k){
akashvibhute 0:30537dec6e0b 111 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 112 }
akashvibhute 0:30537dec6e0b 113 inbuffer[offset+length_group_name-1]=0;
akashvibhute 0:30537dec6e0b 114 this->group_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 115 offset += length_group_name;
akashvibhute 0:30537dec6e0b 116 union {
akashvibhute 0:30537dec6e0b 117 int32_t real;
akashvibhute 0:30537dec6e0b 118 uint32_t base;
akashvibhute 0:30537dec6e0b 119 } u_num_planning_attempts;
akashvibhute 0:30537dec6e0b 120 u_num_planning_attempts.base = 0;
akashvibhute 0:30537dec6e0b 121 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 122 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 123 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 124 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 125 this->num_planning_attempts = u_num_planning_attempts.real;
akashvibhute 0:30537dec6e0b 126 offset += sizeof(this->num_planning_attempts);
akashvibhute 0:30537dec6e0b 127 offset += deserializeAvrFloat64(inbuffer + offset, &(this->allowed_planning_time));
akashvibhute 0:30537dec6e0b 128 return offset;
akashvibhute 0:30537dec6e0b 129 }
akashvibhute 0:30537dec6e0b 130
akashvibhute 0:30537dec6e0b 131 const char * getType(){ return "moveit_msgs/MotionPlanRequest"; };
akashvibhute 0:30537dec6e0b 132 const char * getMD5(){ return "7cd790e04c3a55f6742ec387a72a02d6"; };
akashvibhute 0:30537dec6e0b 133
akashvibhute 0:30537dec6e0b 134 };
akashvibhute 0:30537dec6e0b 135
akashvibhute 0:30537dec6e0b 136 }
akashvibhute 0:30537dec6e0b 137 #endif