Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers LinkState.h Source File

LinkState.h

00001 #ifndef _ROS_gazebo_msgs_LinkState_h
00002 #define _ROS_gazebo_msgs_LinkState_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "geometry_msgs/Pose.h"
00009 #include "geometry_msgs/Twist.h"
00010 
00011 namespace gazebo_msgs
00012 {
00013 
00014   class LinkState : public ros::Msg
00015   {
00016     public:
00017       typedef const char* _link_name_type;
00018       _link_name_type link_name;
00019       typedef geometry_msgs::Pose _pose_type;
00020       _pose_type pose;
00021       typedef geometry_msgs::Twist _twist_type;
00022       _twist_type twist;
00023       typedef const char* _reference_frame_type;
00024       _reference_frame_type reference_frame;
00025 
00026     LinkState():
00027       link_name(""),
00028       pose(),
00029       twist(),
00030       reference_frame("")
00031     {
00032     }
00033 
00034     virtual int serialize(unsigned char *outbuffer) const
00035     {
00036       int offset = 0;
00037       uint32_t length_link_name = strlen(this->link_name);
00038       varToArr(outbuffer + offset, length_link_name);
00039       offset += 4;
00040       memcpy(outbuffer + offset, this->link_name, length_link_name);
00041       offset += length_link_name;
00042       offset += this->pose.serialize(outbuffer + offset);
00043       offset += this->twist.serialize(outbuffer + offset);
00044       uint32_t length_reference_frame = strlen(this->reference_frame);
00045       varToArr(outbuffer + offset, length_reference_frame);
00046       offset += 4;
00047       memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
00048       offset += length_reference_frame;
00049       return offset;
00050     }
00051 
00052     virtual int deserialize(unsigned char *inbuffer)
00053     {
00054       int offset = 0;
00055       uint32_t length_link_name;
00056       arrToVar(length_link_name, (inbuffer + offset));
00057       offset += 4;
00058       for(unsigned int k= offset; k< offset+length_link_name; ++k){
00059           inbuffer[k-1]=inbuffer[k];
00060       }
00061       inbuffer[offset+length_link_name-1]=0;
00062       this->link_name = (char *)(inbuffer + offset-1);
00063       offset += length_link_name;
00064       offset += this->pose.deserialize(inbuffer + offset);
00065       offset += this->twist.deserialize(inbuffer + offset);
00066       uint32_t length_reference_frame;
00067       arrToVar(length_reference_frame, (inbuffer + offset));
00068       offset += 4;
00069       for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
00070           inbuffer[k-1]=inbuffer[k];
00071       }
00072       inbuffer[offset+length_reference_frame-1]=0;
00073       this->reference_frame = (char *)(inbuffer + offset-1);
00074       offset += length_reference_frame;
00075      return offset;
00076     }
00077 
00078     const char * getType(){ return "gazebo_msgs/LinkState"; };
00079     const char * getMD5(){ return "0818ebbf28ce3a08d48ab1eaa7309ebe"; };
00080 
00081   };
00082 
00083 }
00084 #endif