ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
Dependents: rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more
MultiDOFJointState.h
00001 #ifndef _ROS_sensor_msgs_MultiDOFJointState_h 00002 #define _ROS_sensor_msgs_MultiDOFJointState_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 "geometry_msgs/Transform.h" 00010 #include "geometry_msgs/Twist.h" 00011 #include "geometry_msgs/Wrench.h" 00012 00013 namespace sensor_msgs 00014 { 00015 00016 class MultiDOFJointState : public ros::Msg 00017 { 00018 public: 00019 std_msgs::Header header; 00020 uint8_t joint_names_length; 00021 char* st_joint_names; 00022 char* * joint_names; 00023 uint8_t transforms_length; 00024 geometry_msgs::Transform st_transforms; 00025 geometry_msgs::Transform * transforms; 00026 uint8_t twist_length; 00027 geometry_msgs::Twist st_twist; 00028 geometry_msgs::Twist * twist; 00029 uint8_t wrench_length; 00030 geometry_msgs::Wrench st_wrench; 00031 geometry_msgs::Wrench * wrench; 00032 00033 MultiDOFJointState(): 00034 header(), 00035 joint_names_length(0), joint_names(NULL), 00036 transforms_length(0), transforms(NULL), 00037 twist_length(0), twist(NULL), 00038 wrench_length(0), wrench(NULL) 00039 { 00040 } 00041 00042 virtual int serialize(unsigned char *outbuffer) const 00043 { 00044 int offset = 0; 00045 offset += this->header.serialize(outbuffer + offset); 00046 *(outbuffer + offset++) = joint_names_length; 00047 *(outbuffer + offset++) = 0; 00048 *(outbuffer + offset++) = 0; 00049 *(outbuffer + offset++) = 0; 00050 for( uint8_t i = 0; i < joint_names_length; i++){ 00051 uint32_t length_joint_namesi = strlen(this->joint_names[i]); 00052 memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); 00053 offset += 4; 00054 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); 00055 offset += length_joint_namesi; 00056 } 00057 *(outbuffer + offset++) = transforms_length; 00058 *(outbuffer + offset++) = 0; 00059 *(outbuffer + offset++) = 0; 00060 *(outbuffer + offset++) = 0; 00061 for( uint8_t i = 0; i < transforms_length; i++){ 00062 offset += this->transforms[i].serialize(outbuffer + offset); 00063 } 00064 *(outbuffer + offset++) = twist_length; 00065 *(outbuffer + offset++) = 0; 00066 *(outbuffer + offset++) = 0; 00067 *(outbuffer + offset++) = 0; 00068 for( uint8_t i = 0; i < twist_length; i++){ 00069 offset += this->twist[i].serialize(outbuffer + offset); 00070 } 00071 *(outbuffer + offset++) = wrench_length; 00072 *(outbuffer + offset++) = 0; 00073 *(outbuffer + offset++) = 0; 00074 *(outbuffer + offset++) = 0; 00075 for( uint8_t i = 0; i < wrench_length; i++){ 00076 offset += this->wrench[i].serialize(outbuffer + offset); 00077 } 00078 return offset; 00079 } 00080 00081 virtual int deserialize(unsigned char *inbuffer) 00082 { 00083 int offset = 0; 00084 offset += this->header.deserialize(inbuffer + offset); 00085 uint8_t joint_names_lengthT = *(inbuffer + offset++); 00086 if(joint_names_lengthT > joint_names_length) 00087 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); 00088 offset += 3; 00089 joint_names_length = joint_names_lengthT; 00090 for( uint8_t i = 0; i < joint_names_length; i++){ 00091 uint32_t length_st_joint_names; 00092 memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); 00093 offset += 4; 00094 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ 00095 inbuffer[k-1]=inbuffer[k]; 00096 } 00097 inbuffer[offset+length_st_joint_names-1]=0; 00098 this->st_joint_names = (char *)(inbuffer + offset-1); 00099 offset += length_st_joint_names; 00100 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); 00101 } 00102 uint8_t transforms_lengthT = *(inbuffer + offset++); 00103 if(transforms_lengthT > transforms_length) 00104 this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform)); 00105 offset += 3; 00106 transforms_length = transforms_lengthT; 00107 for( uint8_t i = 0; i < transforms_length; i++){ 00108 offset += this->st_transforms.deserialize(inbuffer + offset); 00109 memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform)); 00110 } 00111 uint8_t twist_lengthT = *(inbuffer + offset++); 00112 if(twist_lengthT > twist_length) 00113 this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); 00114 offset += 3; 00115 twist_length = twist_lengthT; 00116 for( uint8_t i = 0; i < twist_length; i++){ 00117 offset += this->st_twist.deserialize(inbuffer + offset); 00118 memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); 00119 } 00120 uint8_t wrench_lengthT = *(inbuffer + offset++); 00121 if(wrench_lengthT > wrench_length) 00122 this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench)); 00123 offset += 3; 00124 wrench_length = wrench_lengthT; 00125 for( uint8_t i = 0; i < wrench_length; i++){ 00126 offset += this->st_wrench.deserialize(inbuffer + offset); 00127 memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench)); 00128 } 00129 return offset; 00130 } 00131 00132 const char * getType(){ return "sensor_msgs/MultiDOFJointState"; }; 00133 const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; }; 00134 00135 }; 00136 00137 } 00138 #endif
Generated on Tue Jul 12 2022 18:39:40 by 1.7.2