kitt_platform
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Macros
MultiDOFJointTrajectoryPoint.h
Go to the documentation of this file.
1 #ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
2 #define _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
3 
4 #include <stdint.h>
5 #include <string.h>
6 #include <stdlib.h>
7 #include "ros/msg.h"
9 #include "geometry_msgs/Twist.h"
10 #include "ros/duration.h"
11 
12 namespace trajectory_msgs
13 {
14 
16  {
17  public:
28 
30  transforms_length(0), transforms(NULL),
31  velocities_length(0), velocities(NULL),
34  {
35  }
36 
37  virtual int serialize(unsigned char *outbuffer) const
38  {
39  int offset = 0;
40  *(outbuffer + offset++) = transforms_length;
41  *(outbuffer + offset++) = 0;
42  *(outbuffer + offset++) = 0;
43  *(outbuffer + offset++) = 0;
44  for( uint8_t i = 0; i < transforms_length; i++){
45  offset += this->transforms[i].serialize(outbuffer + offset);
46  }
47  *(outbuffer + offset++) = velocities_length;
48  *(outbuffer + offset++) = 0;
49  *(outbuffer + offset++) = 0;
50  *(outbuffer + offset++) = 0;
51  for( uint8_t i = 0; i < velocities_length; i++){
52  offset += this->velocities[i].serialize(outbuffer + offset);
53  }
54  *(outbuffer + offset++) = accelerations_length;
55  *(outbuffer + offset++) = 0;
56  *(outbuffer + offset++) = 0;
57  *(outbuffer + offset++) = 0;
58  for( uint8_t i = 0; i < accelerations_length; i++){
59  offset += this->accelerations[i].serialize(outbuffer + offset);
60  }
61  *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF;
62  *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF;
63  *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF;
64  *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF;
65  offset += sizeof(this->time_from_start.sec);
66  *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF;
67  *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF;
68  *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF;
69  *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF;
70  offset += sizeof(this->time_from_start.nsec);
71  return offset;
72  }
73 
74  virtual int deserialize(unsigned char *inbuffer)
75  {
76  int offset = 0;
77  uint8_t transforms_lengthT = *(inbuffer + offset++);
78  if(transforms_lengthT > transforms_length)
79  this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
80  offset += 3;
81  transforms_length = transforms_lengthT;
82  for( uint8_t i = 0; i < transforms_length; i++){
83  offset += this->st_transforms.deserialize(inbuffer + offset);
84  memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
85  }
86  uint8_t velocities_lengthT = *(inbuffer + offset++);
87  if(velocities_lengthT > velocities_length)
88  this->velocities = (geometry_msgs::Twist*)realloc(this->velocities, velocities_lengthT * sizeof(geometry_msgs::Twist));
89  offset += 3;
90  velocities_length = velocities_lengthT;
91  for( uint8_t i = 0; i < velocities_length; i++){
92  offset += this->st_velocities.deserialize(inbuffer + offset);
93  memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(geometry_msgs::Twist));
94  }
95  uint8_t accelerations_lengthT = *(inbuffer + offset++);
96  if(accelerations_lengthT > accelerations_length)
97  this->accelerations = (geometry_msgs::Twist*)realloc(this->accelerations, accelerations_lengthT * sizeof(geometry_msgs::Twist));
98  offset += 3;
99  accelerations_length = accelerations_lengthT;
100  for( uint8_t i = 0; i < accelerations_length; i++){
101  offset += this->st_accelerations.deserialize(inbuffer + offset);
102  memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(geometry_msgs::Twist));
103  }
104  this->time_from_start.sec = ((uint32_t) (*(inbuffer + offset)));
105  this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
106  this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
107  this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
108  offset += sizeof(this->time_from_start.sec);
109  this->time_from_start.nsec = ((uint32_t) (*(inbuffer + offset)));
110  this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
111  this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
112  this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
113  offset += sizeof(this->time_from_start.nsec);
114  return offset;
115  }
116 
117  const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectoryPoint"; };
118  const char * getMD5(){ return "3ebe08d1abd5b65862d50e09430db776"; };
119 
120  };
121 
122 }
123 #endif
geometry_msgs::Transform * transforms
Definition: MultiDOFJointTrajectoryPoint.h:20
virtual int serialize(unsigned char *outbuffer) const
Definition: MultiDOFJointTrajectoryPoint.h:37
uint8_t accelerations_length
Definition: MultiDOFJointTrajectoryPoint.h:24
int32_t sec
Definition: duration.h:48
geometry_msgs::Twist st_velocities
Definition: MultiDOFJointTrajectoryPoint.h:22
virtual int deserialize(unsigned char *inbuffer)
Definition: Twist.h:33
const char * getType()
Definition: MultiDOFJointTrajectoryPoint.h:117
geometry_msgs::Twist * accelerations
Definition: MultiDOFJointTrajectoryPoint.h:26
virtual int deserialize(unsigned char *inbuffer)
Definition: MultiDOFJointTrajectoryPoint.h:74
virtual int serialize(unsigned char *outbuffer) const
Definition: Twist.h:25
geometry_msgs::Twist st_accelerations
Definition: MultiDOFJointTrajectoryPoint.h:25
Definition: Transform.h:14
uint8_t transforms_length
Definition: MultiDOFJointTrajectoryPoint.h:18
geometry_msgs::Twist * velocities
Definition: MultiDOFJointTrajectoryPoint.h:23
Definition: MultiDOFJointTrajectoryPoint.h:15
geometry_msgs::Transform st_transforms
Definition: MultiDOFJointTrajectoryPoint.h:19
const char * getMD5()
Definition: MultiDOFJointTrajectoryPoint.h:118
MultiDOFJointTrajectoryPoint()
Definition: MultiDOFJointTrajectoryPoint.h:29
Definition: Twist.h:13
Definition: duration.h:45
ros::Duration time_from_start
Definition: MultiDOFJointTrajectoryPoint.h:27
uint8_t velocities_length
Definition: MultiDOFJointTrajectoryPoint.h:21
int32_t nsec
Definition: duration.h:48
virtual int deserialize(unsigned char *inbuffer)
Definition: Transform.h:34
virtual int serialize(unsigned char *outbuffer) const
Definition: Transform.h:26
Definition: msg.h:43