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

Dependencies:   BufferedSerial

Committer:
Gary Servin
Date:
Fri Nov 08 14:38:09 2019 -0300
Revision:
0:04ac6be8229a
Initial commit, generated based on a clean melodic-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_sensor_msgs_MultiDOFJointState_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_sensor_msgs_MultiDOFJointState_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "std_msgs/Header.h"
Gary Servin 0:04ac6be8229a 9 #include "geometry_msgs/Transform.h"
Gary Servin 0:04ac6be8229a 10 #include "geometry_msgs/Twist.h"
Gary Servin 0:04ac6be8229a 11 #include "geometry_msgs/Wrench.h"
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 namespace sensor_msgs
Gary Servin 0:04ac6be8229a 14 {
Gary Servin 0:04ac6be8229a 15
Gary Servin 0:04ac6be8229a 16 class MultiDOFJointState : public ros::Msg
Gary Servin 0:04ac6be8229a 17 {
Gary Servin 0:04ac6be8229a 18 public:
Gary Servin 0:04ac6be8229a 19 typedef std_msgs::Header _header_type;
Gary Servin 0:04ac6be8229a 20 _header_type header;
Gary Servin 0:04ac6be8229a 21 uint32_t joint_names_length;
Gary Servin 0:04ac6be8229a 22 typedef char* _joint_names_type;
Gary Servin 0:04ac6be8229a 23 _joint_names_type st_joint_names;
Gary Servin 0:04ac6be8229a 24 _joint_names_type * joint_names;
Gary Servin 0:04ac6be8229a 25 uint32_t transforms_length;
Gary Servin 0:04ac6be8229a 26 typedef geometry_msgs::Transform _transforms_type;
Gary Servin 0:04ac6be8229a 27 _transforms_type st_transforms;
Gary Servin 0:04ac6be8229a 28 _transforms_type * transforms;
Gary Servin 0:04ac6be8229a 29 uint32_t twist_length;
Gary Servin 0:04ac6be8229a 30 typedef geometry_msgs::Twist _twist_type;
Gary Servin 0:04ac6be8229a 31 _twist_type st_twist;
Gary Servin 0:04ac6be8229a 32 _twist_type * twist;
Gary Servin 0:04ac6be8229a 33 uint32_t wrench_length;
Gary Servin 0:04ac6be8229a 34 typedef geometry_msgs::Wrench _wrench_type;
Gary Servin 0:04ac6be8229a 35 _wrench_type st_wrench;
Gary Servin 0:04ac6be8229a 36 _wrench_type * wrench;
Gary Servin 0:04ac6be8229a 37
Gary Servin 0:04ac6be8229a 38 MultiDOFJointState():
Gary Servin 0:04ac6be8229a 39 header(),
Gary Servin 0:04ac6be8229a 40 joint_names_length(0), joint_names(NULL),
Gary Servin 0:04ac6be8229a 41 transforms_length(0), transforms(NULL),
Gary Servin 0:04ac6be8229a 42 twist_length(0), twist(NULL),
Gary Servin 0:04ac6be8229a 43 wrench_length(0), wrench(NULL)
Gary Servin 0:04ac6be8229a 44 {
Gary Servin 0:04ac6be8229a 45 }
Gary Servin 0:04ac6be8229a 46
Gary Servin 0:04ac6be8229a 47 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 48 {
Gary Servin 0:04ac6be8229a 49 int offset = 0;
Gary Servin 0:04ac6be8229a 50 offset += this->header.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 51 *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 52 *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 53 *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 54 *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 55 offset += sizeof(this->joint_names_length);
Gary Servin 0:04ac6be8229a 56 for( uint32_t i = 0; i < joint_names_length; i++){
Gary Servin 0:04ac6be8229a 57 uint32_t length_joint_namesi = strlen(this->joint_names[i]);
Gary Servin 0:04ac6be8229a 58 varToArr(outbuffer + offset, length_joint_namesi);
Gary Servin 0:04ac6be8229a 59 offset += 4;
Gary Servin 0:04ac6be8229a 60 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
Gary Servin 0:04ac6be8229a 61 offset += length_joint_namesi;
Gary Servin 0:04ac6be8229a 62 }
Gary Servin 0:04ac6be8229a 63 *(outbuffer + offset + 0) = (this->transforms_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 64 *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 65 *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 66 *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 67 offset += sizeof(this->transforms_length);
Gary Servin 0:04ac6be8229a 68 for( uint32_t i = 0; i < transforms_length; i++){
Gary Servin 0:04ac6be8229a 69 offset += this->transforms[i].serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 70 }
Gary Servin 0:04ac6be8229a 71 *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 72 *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 73 *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 74 *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 75 offset += sizeof(this->twist_length);
Gary Servin 0:04ac6be8229a 76 for( uint32_t i = 0; i < twist_length; i++){
Gary Servin 0:04ac6be8229a 77 offset += this->twist[i].serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 78 }
Gary Servin 0:04ac6be8229a 79 *(outbuffer + offset + 0) = (this->wrench_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 80 *(outbuffer + offset + 1) = (this->wrench_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 81 *(outbuffer + offset + 2) = (this->wrench_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 3) = (this->wrench_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 offset += sizeof(this->wrench_length);
Gary Servin 0:04ac6be8229a 84 for( uint32_t i = 0; i < wrench_length; i++){
Gary Servin 0:04ac6be8229a 85 offset += this->wrench[i].serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 86 }
Gary Servin 0:04ac6be8229a 87 return offset;
Gary Servin 0:04ac6be8229a 88 }
Gary Servin 0:04ac6be8229a 89
Gary Servin 0:04ac6be8229a 90 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 91 {
Gary Servin 0:04ac6be8229a 92 int offset = 0;
Gary Servin 0:04ac6be8229a 93 offset += this->header.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 94 uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 95 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 96 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 97 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 98 offset += sizeof(this->joint_names_length);
Gary Servin 0:04ac6be8229a 99 if(joint_names_lengthT > joint_names_length)
Gary Servin 0:04ac6be8229a 100 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
Gary Servin 0:04ac6be8229a 101 joint_names_length = joint_names_lengthT;
Gary Servin 0:04ac6be8229a 102 for( uint32_t i = 0; i < joint_names_length; i++){
Gary Servin 0:04ac6be8229a 103 uint32_t length_st_joint_names;
Gary Servin 0:04ac6be8229a 104 arrToVar(length_st_joint_names, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 105 offset += 4;
Gary Servin 0:04ac6be8229a 106 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
Gary Servin 0:04ac6be8229a 107 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 108 }
Gary Servin 0:04ac6be8229a 109 inbuffer[offset+length_st_joint_names-1]=0;
Gary Servin 0:04ac6be8229a 110 this->st_joint_names = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 111 offset += length_st_joint_names;
Gary Servin 0:04ac6be8229a 112 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
Gary Servin 0:04ac6be8229a 113 }
Gary Servin 0:04ac6be8229a 114 uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 115 transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 116 transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 117 transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 118 offset += sizeof(this->transforms_length);
Gary Servin 0:04ac6be8229a 119 if(transforms_lengthT > transforms_length)
Gary Servin 0:04ac6be8229a 120 this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
Gary Servin 0:04ac6be8229a 121 transforms_length = transforms_lengthT;
Gary Servin 0:04ac6be8229a 122 for( uint32_t i = 0; i < transforms_length; i++){
Gary Servin 0:04ac6be8229a 123 offset += this->st_transforms.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 124 memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
Gary Servin 0:04ac6be8229a 125 }
Gary Servin 0:04ac6be8229a 126 uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 127 twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 128 twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 129 twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 130 offset += sizeof(this->twist_length);
Gary Servin 0:04ac6be8229a 131 if(twist_lengthT > twist_length)
Gary Servin 0:04ac6be8229a 132 this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
Gary Servin 0:04ac6be8229a 133 twist_length = twist_lengthT;
Gary Servin 0:04ac6be8229a 134 for( uint32_t i = 0; i < twist_length; i++){
Gary Servin 0:04ac6be8229a 135 offset += this->st_twist.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 136 memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
Gary Servin 0:04ac6be8229a 137 }
Gary Servin 0:04ac6be8229a 138 uint32_t wrench_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 139 wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 140 wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 141 wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 142 offset += sizeof(this->wrench_length);
Gary Servin 0:04ac6be8229a 143 if(wrench_lengthT > wrench_length)
Gary Servin 0:04ac6be8229a 144 this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
Gary Servin 0:04ac6be8229a 145 wrench_length = wrench_lengthT;
Gary Servin 0:04ac6be8229a 146 for( uint32_t i = 0; i < wrench_length; i++){
Gary Servin 0:04ac6be8229a 147 offset += this->st_wrench.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 148 memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench));
Gary Servin 0:04ac6be8229a 149 }
Gary Servin 0:04ac6be8229a 150 return offset;
Gary Servin 0:04ac6be8229a 151 }
Gary Servin 0:04ac6be8229a 152
Gary Servin 0:04ac6be8229a 153 const char * getType(){ return "sensor_msgs/MultiDOFJointState"; };
Gary Servin 0:04ac6be8229a 154 const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; };
Gary Servin 0:04ac6be8229a 155
Gary Servin 0:04ac6be8229a 156 };
Gary Servin 0:04ac6be8229a 157
Gary Servin 0:04ac6be8229a 158 }
Gary Servin 0:04ac6be8229a 159 #endif