kitt_platform
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Macros
MultiDOFJointState.h
Go to the documentation of this file.
1 #ifndef _ROS_sensor_msgs_MultiDOFJointState_h
2 #define _ROS_sensor_msgs_MultiDOFJointState_h
3 
4 #include <stdint.h>
5 #include <string.h>
6 #include <stdlib.h>
7 #include "ros/msg.h"
8 #include "std_msgs/Header.h"
10 #include "geometry_msgs/Twist.h"
11 #include "geometry_msgs/Wrench.h"
12 
13 namespace sensor_msgs
14 {
15 
17  {
18  public:
22  char* * joint_names;
26  uint8_t twist_length;
29  uint8_t wrench_length;
32 
34  header(),
36  transforms_length(0), transforms(NULL),
37  twist_length(0), twist(NULL),
38  wrench_length(0), wrench(NULL)
39  {
40  }
41 
42  virtual int serialize(unsigned char *outbuffer) const
43  {
44  int offset = 0;
45  offset += this->header.serialize(outbuffer + offset);
46  *(outbuffer + offset++) = joint_names_length;
47  *(outbuffer + offset++) = 0;
48  *(outbuffer + offset++) = 0;
49  *(outbuffer + offset++) = 0;
50  for( uint8_t i = 0; i < joint_names_length; i++){
51  uint32_t length_joint_namesi = strlen(this->joint_names[i]);
52  memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
53  offset += 4;
54  memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
55  offset += length_joint_namesi;
56  }
57  *(outbuffer + offset++) = transforms_length;
58  *(outbuffer + offset++) = 0;
59  *(outbuffer + offset++) = 0;
60  *(outbuffer + offset++) = 0;
61  for( uint8_t i = 0; i < transforms_length; i++){
62  offset += this->transforms[i].serialize(outbuffer + offset);
63  }
64  *(outbuffer + offset++) = twist_length;
65  *(outbuffer + offset++) = 0;
66  *(outbuffer + offset++) = 0;
67  *(outbuffer + offset++) = 0;
68  for( uint8_t i = 0; i < twist_length; i++){
69  offset += this->twist[i].serialize(outbuffer + offset);
70  }
71  *(outbuffer + offset++) = wrench_length;
72  *(outbuffer + offset++) = 0;
73  *(outbuffer + offset++) = 0;
74  *(outbuffer + offset++) = 0;
75  for( uint8_t i = 0; i < wrench_length; i++){
76  offset += this->wrench[i].serialize(outbuffer + offset);
77  }
78  return offset;
79  }
80 
81  virtual int deserialize(unsigned char *inbuffer)
82  {
83  int offset = 0;
84  offset += this->header.deserialize(inbuffer + offset);
85  uint8_t joint_names_lengthT = *(inbuffer + offset++);
86  if(joint_names_lengthT > joint_names_length)
87  this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
88  offset += 3;
89  joint_names_length = joint_names_lengthT;
90  for( uint8_t i = 0; i < joint_names_length; i++){
91  uint32_t length_st_joint_names;
92  memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
93  offset += 4;
94  for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
95  inbuffer[k-1]=inbuffer[k];
96  }
97  inbuffer[offset+length_st_joint_names-1]=0;
98  this->st_joint_names = (char *)(inbuffer + offset-1);
99  offset += length_st_joint_names;
100  memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
101  }
102  uint8_t transforms_lengthT = *(inbuffer + offset++);
103  if(transforms_lengthT > transforms_length)
104  this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
105  offset += 3;
106  transforms_length = transforms_lengthT;
107  for( uint8_t i = 0; i < transforms_length; i++){
108  offset += this->st_transforms.deserialize(inbuffer + offset);
109  memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
110  }
111  uint8_t twist_lengthT = *(inbuffer + offset++);
112  if(twist_lengthT > twist_length)
113  this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
114  offset += 3;
115  twist_length = twist_lengthT;
116  for( uint8_t i = 0; i < twist_length; i++){
117  offset += this->st_twist.deserialize(inbuffer + offset);
118  memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
119  }
120  uint8_t wrench_lengthT = *(inbuffer + offset++);
121  if(wrench_lengthT > wrench_length)
122  this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
123  offset += 3;
124  wrench_length = wrench_lengthT;
125  for( uint8_t i = 0; i < wrench_length; i++){
126  offset += this->st_wrench.deserialize(inbuffer + offset);
127  memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench));
128  }
129  return offset;
130  }
131 
132  const char * getType(){ return "sensor_msgs/MultiDOFJointState"; };
133  const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; };
134 
135  };
136 
137 }
138 #endif
virtual int deserialize(unsigned char *inbuffer)
Definition: Header.h:53
geometry_msgs::Twist st_twist
Definition: MultiDOFJointState.h:27
virtual int serialize(unsigned char *outbuffer) const
Definition: MultiDOFJointState.h:42
uint8_t twist_length
Definition: MultiDOFJointState.h:26
virtual int deserialize(unsigned char *inbuffer)
Definition: Twist.h:33
virtual int deserialize(unsigned char *inbuffer)
Definition: MultiDOFJointState.h:81
virtual int serialize(unsigned char *outbuffer) const
Definition: Header.h:27
geometry_msgs::Twist * twist
Definition: MultiDOFJointState.h:28
uint8_t transforms_length
Definition: MultiDOFJointState.h:23
virtual int serialize(unsigned char *outbuffer) const
Definition: Twist.h:25
Definition: Wrench.h:13
geometry_msgs::Wrench * wrench
Definition: MultiDOFJointState.h:31
uint8_t wrench_length
Definition: MultiDOFJointState.h:29
Definition: Transform.h:14
uint8_t joint_names_length
Definition: MultiDOFJointState.h:20
MultiDOFJointState()
Definition: MultiDOFJointState.h:33
std_msgs::Header header
Definition: MultiDOFJointState.h:19
Definition: Header.h:13
geometry_msgs::Wrench st_wrench
Definition: MultiDOFJointState.h:30
Definition: MultiDOFJointState.h:16
virtual int deserialize(unsigned char *inbuffer)
Definition: Wrench.h:33
const char * getType()
Definition: MultiDOFJointState.h:132
virtual int serialize(unsigned char *outbuffer) const
Definition: Wrench.h:25
Definition: Twist.h:13
geometry_msgs::Transform * transforms
Definition: MultiDOFJointState.h:25
virtual int deserialize(unsigned char *inbuffer)
Definition: Transform.h:34
virtual int serialize(unsigned char *outbuffer) const
Definition: Transform.h:26
char * st_joint_names
Definition: MultiDOFJointState.h:21
Definition: msg.h:43
geometry_msgs::Transform st_transforms
Definition: MultiDOFJointState.h:24
char ** joint_names
Definition: MultiDOFJointState.h:22
const char * getMD5()
Definition: MultiDOFJointState.h:133