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_control_msgs_FollowJointTrajectoryGoal_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_control_msgs_FollowJointTrajectoryGoal_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 "control_msgs/JointTolerance.h"
akashvibhute 0:30537dec6e0b 10 #include "ros/duration.h"
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 namespace control_msgs
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 class FollowJointTrajectoryGoal : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 trajectory_msgs::JointTrajectory trajectory;
akashvibhute 0:30537dec6e0b 19 uint8_t path_tolerance_length;
akashvibhute 0:30537dec6e0b 20 control_msgs::JointTolerance st_path_tolerance;
akashvibhute 0:30537dec6e0b 21 control_msgs::JointTolerance * path_tolerance;
akashvibhute 0:30537dec6e0b 22 uint8_t goal_tolerance_length;
akashvibhute 0:30537dec6e0b 23 control_msgs::JointTolerance st_goal_tolerance;
akashvibhute 0:30537dec6e0b 24 control_msgs::JointTolerance * goal_tolerance;
akashvibhute 0:30537dec6e0b 25 ros::Duration goal_time_tolerance;
akashvibhute 0:30537dec6e0b 26
akashvibhute 0:30537dec6e0b 27 FollowJointTrajectoryGoal():
akashvibhute 0:30537dec6e0b 28 trajectory(),
akashvibhute 0:30537dec6e0b 29 path_tolerance_length(0), path_tolerance(NULL),
akashvibhute 0:30537dec6e0b 30 goal_tolerance_length(0), goal_tolerance(NULL),
akashvibhute 0:30537dec6e0b 31 goal_time_tolerance()
akashvibhute 0:30537dec6e0b 32 {
akashvibhute 0:30537dec6e0b 33 }
akashvibhute 0:30537dec6e0b 34
akashvibhute 0:30537dec6e0b 35 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 36 {
akashvibhute 0:30537dec6e0b 37 int offset = 0;
akashvibhute 0:30537dec6e0b 38 offset += this->trajectory.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 39 *(outbuffer + offset++) = path_tolerance_length;
akashvibhute 0:30537dec6e0b 40 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 41 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 42 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 43 for( uint8_t i = 0; i < path_tolerance_length; i++){
akashvibhute 0:30537dec6e0b 44 offset += this->path_tolerance[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 45 }
akashvibhute 0:30537dec6e0b 46 *(outbuffer + offset++) = goal_tolerance_length;
akashvibhute 0:30537dec6e0b 47 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 48 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 50 for( uint8_t i = 0; i < goal_tolerance_length; i++){
akashvibhute 0:30537dec6e0b 51 offset += this->goal_tolerance[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 52 }
akashvibhute 0:30537dec6e0b 53 *(outbuffer + offset + 0) = (this->goal_time_tolerance.sec >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 54 *(outbuffer + offset + 1) = (this->goal_time_tolerance.sec >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 55 *(outbuffer + offset + 2) = (this->goal_time_tolerance.sec >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 56 *(outbuffer + offset + 3) = (this->goal_time_tolerance.sec >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 57 offset += sizeof(this->goal_time_tolerance.sec);
akashvibhute 0:30537dec6e0b 58 *(outbuffer + offset + 0) = (this->goal_time_tolerance.nsec >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 59 *(outbuffer + offset + 1) = (this->goal_time_tolerance.nsec >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 60 *(outbuffer + offset + 2) = (this->goal_time_tolerance.nsec >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 61 *(outbuffer + offset + 3) = (this->goal_time_tolerance.nsec >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 62 offset += sizeof(this->goal_time_tolerance.nsec);
akashvibhute 0:30537dec6e0b 63 return offset;
akashvibhute 0:30537dec6e0b 64 }
akashvibhute 0:30537dec6e0b 65
akashvibhute 0:30537dec6e0b 66 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 67 {
akashvibhute 0:30537dec6e0b 68 int offset = 0;
akashvibhute 0:30537dec6e0b 69 offset += this->trajectory.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 70 uint8_t path_tolerance_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 71 if(path_tolerance_lengthT > path_tolerance_length)
akashvibhute 0:30537dec6e0b 72 this->path_tolerance = (control_msgs::JointTolerance*)realloc(this->path_tolerance, path_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
akashvibhute 0:30537dec6e0b 73 offset += 3;
akashvibhute 0:30537dec6e0b 74 path_tolerance_length = path_tolerance_lengthT;
akashvibhute 0:30537dec6e0b 75 for( uint8_t i = 0; i < path_tolerance_length; i++){
akashvibhute 0:30537dec6e0b 76 offset += this->st_path_tolerance.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 77 memcpy( &(this->path_tolerance[i]), &(this->st_path_tolerance), sizeof(control_msgs::JointTolerance));
akashvibhute 0:30537dec6e0b 78 }
akashvibhute 0:30537dec6e0b 79 uint8_t goal_tolerance_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 80 if(goal_tolerance_lengthT > goal_tolerance_length)
akashvibhute 0:30537dec6e0b 81 this->goal_tolerance = (control_msgs::JointTolerance*)realloc(this->goal_tolerance, goal_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
akashvibhute 0:30537dec6e0b 82 offset += 3;
akashvibhute 0:30537dec6e0b 83 goal_tolerance_length = goal_tolerance_lengthT;
akashvibhute 0:30537dec6e0b 84 for( uint8_t i = 0; i < goal_tolerance_length; i++){
akashvibhute 0:30537dec6e0b 85 offset += this->st_goal_tolerance.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 86 memcpy( &(this->goal_tolerance[i]), &(this->st_goal_tolerance), sizeof(control_msgs::JointTolerance));
akashvibhute 0:30537dec6e0b 87 }
akashvibhute 0:30537dec6e0b 88 this->goal_time_tolerance.sec = ((uint32_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 89 this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 90 this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 91 this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 92 offset += sizeof(this->goal_time_tolerance.sec);
akashvibhute 0:30537dec6e0b 93 this->goal_time_tolerance.nsec = ((uint32_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 94 this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 95 this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 96 this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 97 offset += sizeof(this->goal_time_tolerance.nsec);
akashvibhute 0:30537dec6e0b 98 return offset;
akashvibhute 0:30537dec6e0b 99 }
akashvibhute 0:30537dec6e0b 100
akashvibhute 0:30537dec6e0b 101 const char * getType(){ return "control_msgs/FollowJointTrajectoryGoal"; };
akashvibhute 0:30537dec6e0b 102 const char * getMD5(){ return "69636787b6ecbde4d61d711979bc7ecb"; };
akashvibhute 0:30537dec6e0b 103
akashvibhute 0:30537dec6e0b 104 };
akashvibhute 0:30537dec6e0b 105
akashvibhute 0:30537dec6e0b 106 }
akashvibhute 0:30537dec6e0b 107 #endif