This is a fork from the original, including a small change in the buffer size of the hardware interface (increased to 2048) and decreasing the number of publishers and subscribers to 5. Besides, the library about the message Adc.h was modified so as to increase the number of available Adc channels to be read ( from 6 to 7 ) For this modification, a change in checksum was required

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
jacobepfl1692
Date:
Tue Oct 17 18:49:03 2017 +0000
Revision:
2:9114cc24ddcf
Parent:
0:9e9b7db60fd5
I increased the channels of the ADC to 6 (hence change in checksum) because my application needed it (STM32f407V6)

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_nav_msgs_Odometry_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_nav_msgs_Odometry_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 "std_msgs/Header.h"
garyservin 0:9e9b7db60fd5 9 #include "geometry_msgs/PoseWithCovariance.h"
garyservin 0:9e9b7db60fd5 10 #include "geometry_msgs/TwistWithCovariance.h"
garyservin 0:9e9b7db60fd5 11
garyservin 0:9e9b7db60fd5 12 namespace nav_msgs
garyservin 0:9e9b7db60fd5 13 {
garyservin 0:9e9b7db60fd5 14
garyservin 0:9e9b7db60fd5 15 class Odometry : public ros::Msg
garyservin 0:9e9b7db60fd5 16 {
garyservin 0:9e9b7db60fd5 17 public:
garyservin 0:9e9b7db60fd5 18 typedef std_msgs::Header _header_type;
garyservin 0:9e9b7db60fd5 19 _header_type header;
garyservin 0:9e9b7db60fd5 20 typedef const char* _child_frame_id_type;
garyservin 0:9e9b7db60fd5 21 _child_frame_id_type child_frame_id;
garyservin 0:9e9b7db60fd5 22 typedef geometry_msgs::PoseWithCovariance _pose_type;
garyservin 0:9e9b7db60fd5 23 _pose_type pose;
garyservin 0:9e9b7db60fd5 24 typedef geometry_msgs::TwistWithCovariance _twist_type;
garyservin 0:9e9b7db60fd5 25 _twist_type twist;
garyservin 0:9e9b7db60fd5 26
garyservin 0:9e9b7db60fd5 27 Odometry():
garyservin 0:9e9b7db60fd5 28 header(),
garyservin 0:9e9b7db60fd5 29 child_frame_id(""),
garyservin 0:9e9b7db60fd5 30 pose(),
garyservin 0:9e9b7db60fd5 31 twist()
garyservin 0:9e9b7db60fd5 32 {
garyservin 0:9e9b7db60fd5 33 }
garyservin 0:9e9b7db60fd5 34
garyservin 0:9e9b7db60fd5 35 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 36 {
garyservin 0:9e9b7db60fd5 37 int offset = 0;
garyservin 0:9e9b7db60fd5 38 offset += this->header.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 39 uint32_t length_child_frame_id = strlen(this->child_frame_id);
garyservin 0:9e9b7db60fd5 40 varToArr(outbuffer + offset, length_child_frame_id);
garyservin 0:9e9b7db60fd5 41 offset += 4;
garyservin 0:9e9b7db60fd5 42 memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id);
garyservin 0:9e9b7db60fd5 43 offset += length_child_frame_id;
garyservin 0:9e9b7db60fd5 44 offset += this->pose.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 45 offset += this->twist.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 46 return offset;
garyservin 0:9e9b7db60fd5 47 }
garyservin 0:9e9b7db60fd5 48
garyservin 0:9e9b7db60fd5 49 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 50 {
garyservin 0:9e9b7db60fd5 51 int offset = 0;
garyservin 0:9e9b7db60fd5 52 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 53 uint32_t length_child_frame_id;
garyservin 0:9e9b7db60fd5 54 arrToVar(length_child_frame_id, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 55 offset += 4;
garyservin 0:9e9b7db60fd5 56 for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
garyservin 0:9e9b7db60fd5 57 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 58 }
garyservin 0:9e9b7db60fd5 59 inbuffer[offset+length_child_frame_id-1]=0;
garyservin 0:9e9b7db60fd5 60 this->child_frame_id = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 61 offset += length_child_frame_id;
garyservin 0:9e9b7db60fd5 62 offset += this->pose.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 63 offset += this->twist.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 64 return offset;
garyservin 0:9e9b7db60fd5 65 }
garyservin 0:9e9b7db60fd5 66
garyservin 0:9e9b7db60fd5 67 const char * getType(){ return "nav_msgs/Odometry"; };
garyservin 0:9e9b7db60fd5 68 const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; };
garyservin 0:9e9b7db60fd5 69
garyservin 0:9e9b7db60fd5 70 };
garyservin 0:9e9b7db60fd5 71
garyservin 0:9e9b7db60fd5 72 }
garyservin 0:9e9b7db60fd5 73 #endif