ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

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       const char* link_name;
00018       geometry_msgs::Pose pose;
00019       geometry_msgs::Twist twist;
00020       const char* reference_frame;
00021 
00022     LinkState():
00023       link_name(""),
00024       pose(),
00025       twist(),
00026       reference_frame("")
00027     {
00028     }
00029 
00030     virtual int serialize(unsigned char *outbuffer) const
00031     {
00032       int offset = 0;
00033       uint32_t length_link_name = strlen(this->link_name);
00034       memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
00035       offset += 4;
00036       memcpy(outbuffer + offset, this->link_name, length_link_name);
00037       offset += length_link_name;
00038       offset += this->pose.serialize(outbuffer + offset);
00039       offset += this->twist.serialize(outbuffer + offset);
00040       uint32_t length_reference_frame = strlen(this->reference_frame);
00041       memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
00042       offset += 4;
00043       memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
00044       offset += length_reference_frame;
00045       return offset;
00046     }
00047 
00048     virtual int deserialize(unsigned char *inbuffer)
00049     {
00050       int offset = 0;
00051       uint32_t length_link_name;
00052       memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
00053       offset += 4;
00054       for(unsigned int k= offset; k< offset+length_link_name; ++k){
00055           inbuffer[k-1]=inbuffer[k];
00056       }
00057       inbuffer[offset+length_link_name-1]=0;
00058       this->link_name = (char *)(inbuffer + offset-1);
00059       offset += length_link_name;
00060       offset += this->pose.deserialize(inbuffer + offset);
00061       offset += this->twist.deserialize(inbuffer + offset);
00062       uint32_t length_reference_frame;
00063       memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
00064       offset += 4;
00065       for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
00066           inbuffer[k-1]=inbuffer[k];
00067       }
00068       inbuffer[offset+length_reference_frame-1]=0;
00069       this->reference_frame = (char *)(inbuffer + offset-1);
00070       offset += length_reference_frame;
00071      return offset;
00072     }
00073 
00074     const char * getType(){ return "gazebo_msgs/LinkState"; };
00075     const char * getMD5(){ return "0818ebbf28ce3a08d48ab1eaa7309ebe"; };
00076 
00077   };
00078 
00079 }
00080 #endif