JointTrajectoryControllerState.h
Go to the documentation of this file.
00001 #ifndef _ROS_control_msgs_JointTrajectoryControllerState_h
00002 #define _ROS_control_msgs_JointTrajectoryControllerState_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "trajectory_msgs/JointTrajectoryPoint.h"
00010 
00011 namespace control_msgs
00012 {
00013 
00014   class JointTrajectoryControllerState : public ros::Msg
00015   {
00016     public:
00017       std_msgs::Header header;
00018       uint8_t joint_names_length;
00019       char* st_joint_names;
00020       char* * joint_names;
00021       trajectory_msgs::JointTrajectoryPoint desired;
00022       trajectory_msgs::JointTrajectoryPoint actual;
00023       trajectory_msgs::JointTrajectoryPoint error;
00024 
00025     virtual int serialize(unsigned char *outbuffer) const
00026     {
00027       int offset = 0;
00028       offset += this->header.serialize(outbuffer + offset);
00029       *(outbuffer + offset++) = joint_names_length;
00030       *(outbuffer + offset++) = 0;
00031       *(outbuffer + offset++) = 0;
00032       *(outbuffer + offset++) = 0;
00033       for( uint8_t i = 0; i < joint_names_length; i++){
00034       uint32_t length_joint_namesi = strlen(this->joint_names[i]);
00035       memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
00036       offset += 4;
00037       memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
00038       offset += length_joint_namesi;
00039       }
00040       offset += this->desired.serialize(outbuffer + offset);
00041       offset += this->actual.serialize(outbuffer + offset);
00042       offset += this->error.serialize(outbuffer + offset);
00043       return offset;
00044     }
00045 
00046     virtual int deserialize(unsigned char *inbuffer)
00047     {
00048       int offset = 0;
00049       offset += this->header.deserialize(inbuffer + offset);
00050       uint8_t joint_names_lengthT = *(inbuffer + offset++);
00051       if(joint_names_lengthT > joint_names_length)
00052         this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
00053       offset += 3;
00054       joint_names_length = joint_names_lengthT;
00055       for( uint8_t i = 0; i < joint_names_length; i++){
00056       uint32_t length_st_joint_names;
00057       memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
00058       offset += 4;
00059       for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
00060           inbuffer[k-1]=inbuffer[k];
00061       }
00062       inbuffer[offset+length_st_joint_names-1]=0;
00063       this->st_joint_names = (char *)(inbuffer + offset-1);
00064       offset += length_st_joint_names;
00065         memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
00066       }
00067       offset += this->desired.deserialize(inbuffer + offset);
00068       offset += this->actual.deserialize(inbuffer + offset);
00069       offset += this->error.deserialize(inbuffer + offset);
00070      return offset;
00071     }
00072 
00073     const char * getType(){ return "control_msgs/JointTrajectoryControllerState"; };
00074     const char * getMD5(){ return "10817c60c2486ef6b33e97dcd87f4474"; };
00075 
00076   };
00077 
00078 }
00079 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:49