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!

Revision:
0:30537dec6e0b
diff -r 000000000000 -r 30537dec6e0b moveit_msgs/TrajectoryConstraints.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/moveit_msgs/TrajectoryConstraints.h	Sun Feb 15 10:53:43 2015 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_moveit_msgs_TrajectoryConstraints_h
+#define _ROS_moveit_msgs_TrajectoryConstraints_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "moveit_msgs/Constraints.h"
+
+namespace moveit_msgs
+{
+
+  class TrajectoryConstraints : public ros::Msg
+  {
+    public:
+      uint8_t constraints_length;
+      moveit_msgs::Constraints st_constraints;
+      moveit_msgs::Constraints * constraints;
+
+    TrajectoryConstraints():
+      constraints_length(0), constraints(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = constraints_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < constraints_length; i++){
+      offset += this->constraints[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t constraints_lengthT = *(inbuffer + offset++);
+      if(constraints_lengthT > constraints_length)
+        this->constraints = (moveit_msgs::Constraints*)realloc(this->constraints, constraints_lengthT * sizeof(moveit_msgs::Constraints));
+      offset += 3;
+      constraints_length = constraints_lengthT;
+      for( uint8_t i = 0; i < constraints_length; i++){
+      offset += this->st_constraints.deserialize(inbuffer + offset);
+        memcpy( &(this->constraints[i]), &(this->st_constraints), sizeof(moveit_msgs::Constraints));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "moveit_msgs/TrajectoryConstraints"; };
+    const char * getMD5(){ return "461e1a732dfebb01e7d6c75d51a51eac"; };
+
+  };
+
+}
+#endif