It has only one change from original one. I added robotfeedback message on it.
Dependents: RobotFeedback mobileRobotITU
Fork of ros_lib_indigo by
Diff: gazebo_msgs/LinkStates.h
- Revision:
- 0:fd24f7ca9688
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/LinkStates.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/LinkStates.h Thu Mar 31 14:22:59 2016 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_gazebo_msgs_LinkStates_h +#define _ROS_gazebo_msgs_LinkStates_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Twist.h" + +namespace gazebo_msgs +{ + + class LinkStates : public ros::Msg + { + public: + uint8_t name_length; + char* st_name; + char* * name; + uint8_t pose_length; + geometry_msgs::Pose st_pose; + geometry_msgs::Pose * pose; + uint8_t twist_length; + geometry_msgs::Twist st_twist; + geometry_msgs::Twist * twist; + + LinkStates(): + name_length(0), name(NULL), + pose_length(0), pose(NULL), + twist_length(0), twist(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = name_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_namei = strlen(this->name[i]); + memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name[i], length_namei); + offset += length_namei; + } + *(outbuffer + offset++) = pose_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->pose[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = twist_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->twist[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t name_lengthT = *(inbuffer + offset++); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + offset += 3; + name_length = name_lengthT; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_st_name; + memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_name-1]=0; + this->st_name = (char *)(inbuffer + offset-1); + offset += length_st_name; + memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); + } + uint8_t pose_lengthT = *(inbuffer + offset++); + if(pose_lengthT > pose_length) + this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + pose_length = pose_lengthT; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->st_pose.deserialize(inbuffer + offset); + memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose)); + } + uint8_t twist_lengthT = *(inbuffer + offset++); + if(twist_lengthT > twist_length) + this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); + offset += 3; + twist_length = twist_lengthT; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->st_twist.deserialize(inbuffer + offset); + memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); + } + return offset; + } + + const char * getType(){ return "gazebo_msgs/LinkStates"; }; + const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; }; + + }; + +} +#endif \ No newline at end of file