Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
jvfausto
Date:
Fri Nov 02 21:48:22 2018 +0000
Revision:
2:ab8333331642
Parent:
0:9e9b7db60fd5
Working towards twists

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_geometry_msgs_Twist_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_geometry_msgs_Twist_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "geometry_msgs/Vector3.h"
garyservin 0:9e9b7db60fd5 9
garyservin 0:9e9b7db60fd5 10 namespace geometry_msgs
garyservin 0:9e9b7db60fd5 11 {
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 class Twist : public ros::Msg
garyservin 0:9e9b7db60fd5 14 {
garyservin 0:9e9b7db60fd5 15 public:
garyservin 0:9e9b7db60fd5 16 typedef geometry_msgs::Vector3 _linear_type;
garyservin 0:9e9b7db60fd5 17 _linear_type linear;
garyservin 0:9e9b7db60fd5 18 typedef geometry_msgs::Vector3 _angular_type;
garyservin 0:9e9b7db60fd5 19 _angular_type angular;
garyservin 0:9e9b7db60fd5 20
garyservin 0:9e9b7db60fd5 21 Twist():
garyservin 0:9e9b7db60fd5 22 linear(),
garyservin 0:9e9b7db60fd5 23 angular()
garyservin 0:9e9b7db60fd5 24 {
garyservin 0:9e9b7db60fd5 25 }
garyservin 0:9e9b7db60fd5 26
garyservin 0:9e9b7db60fd5 27 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 28 {
garyservin 0:9e9b7db60fd5 29 int offset = 0;
garyservin 0:9e9b7db60fd5 30 offset += this->linear.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 31 offset += this->angular.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 32 return offset;
garyservin 0:9e9b7db60fd5 33 }
garyservin 0:9e9b7db60fd5 34
garyservin 0:9e9b7db60fd5 35 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 36 {
garyservin 0:9e9b7db60fd5 37 int offset = 0;
garyservin 0:9e9b7db60fd5 38 offset += this->linear.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 39 offset += this->angular.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 40 return offset;
garyservin 0:9e9b7db60fd5 41 }
garyservin 0:9e9b7db60fd5 42
garyservin 0:9e9b7db60fd5 43 const char * getType(){ return "geometry_msgs/Twist"; };
garyservin 0:9e9b7db60fd5 44 const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; };
garyservin 0:9e9b7db60fd5 45
garyservin 0:9e9b7db60fd5 46 };
garyservin 0:9e9b7db60fd5 47
garyservin 0:9e9b7db60fd5 48 }
garyservin 0:9e9b7db60fd5 49 #endif