hairo

Dependencies:   mbed BufferedSerial

Committer:
tknara
Date:
Tue Dec 04 00:14:32 2018 +0000
Revision:
4:bcdd99711326
Parent:
0:9e9b7db60fd5
test

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_rosgraph_msgs_TopicStatistics_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_rosgraph_msgs_TopicStatistics_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 "ros/time.h"
garyservin 0:9e9b7db60fd5 9 #include "ros/duration.h"
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 namespace rosgraph_msgs
garyservin 0:9e9b7db60fd5 12 {
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 class TopicStatistics : public ros::Msg
garyservin 0:9e9b7db60fd5 15 {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 typedef const char* _topic_type;
garyservin 0:9e9b7db60fd5 18 _topic_type topic;
garyservin 0:9e9b7db60fd5 19 typedef const char* _node_pub_type;
garyservin 0:9e9b7db60fd5 20 _node_pub_type node_pub;
garyservin 0:9e9b7db60fd5 21 typedef const char* _node_sub_type;
garyservin 0:9e9b7db60fd5 22 _node_sub_type node_sub;
garyservin 0:9e9b7db60fd5 23 typedef ros::Time _window_start_type;
garyservin 0:9e9b7db60fd5 24 _window_start_type window_start;
garyservin 0:9e9b7db60fd5 25 typedef ros::Time _window_stop_type;
garyservin 0:9e9b7db60fd5 26 _window_stop_type window_stop;
garyservin 0:9e9b7db60fd5 27 typedef int32_t _delivered_msgs_type;
garyservin 0:9e9b7db60fd5 28 _delivered_msgs_type delivered_msgs;
garyservin 0:9e9b7db60fd5 29 typedef int32_t _dropped_msgs_type;
garyservin 0:9e9b7db60fd5 30 _dropped_msgs_type dropped_msgs;
garyservin 0:9e9b7db60fd5 31 typedef int32_t _traffic_type;
garyservin 0:9e9b7db60fd5 32 _traffic_type traffic;
garyservin 0:9e9b7db60fd5 33 typedef ros::Duration _period_mean_type;
garyservin 0:9e9b7db60fd5 34 _period_mean_type period_mean;
garyservin 0:9e9b7db60fd5 35 typedef ros::Duration _period_stddev_type;
garyservin 0:9e9b7db60fd5 36 _period_stddev_type period_stddev;
garyservin 0:9e9b7db60fd5 37 typedef ros::Duration _period_max_type;
garyservin 0:9e9b7db60fd5 38 _period_max_type period_max;
garyservin 0:9e9b7db60fd5 39 typedef ros::Duration _stamp_age_mean_type;
garyservin 0:9e9b7db60fd5 40 _stamp_age_mean_type stamp_age_mean;
garyservin 0:9e9b7db60fd5 41 typedef ros::Duration _stamp_age_stddev_type;
garyservin 0:9e9b7db60fd5 42 _stamp_age_stddev_type stamp_age_stddev;
garyservin 0:9e9b7db60fd5 43 typedef ros::Duration _stamp_age_max_type;
garyservin 0:9e9b7db60fd5 44 _stamp_age_max_type stamp_age_max;
garyservin 0:9e9b7db60fd5 45
garyservin 0:9e9b7db60fd5 46 TopicStatistics():
garyservin 0:9e9b7db60fd5 47 topic(""),
garyservin 0:9e9b7db60fd5 48 node_pub(""),
garyservin 0:9e9b7db60fd5 49 node_sub(""),
garyservin 0:9e9b7db60fd5 50 window_start(),
garyservin 0:9e9b7db60fd5 51 window_stop(),
garyservin 0:9e9b7db60fd5 52 delivered_msgs(0),
garyservin 0:9e9b7db60fd5 53 dropped_msgs(0),
garyservin 0:9e9b7db60fd5 54 traffic(0),
garyservin 0:9e9b7db60fd5 55 period_mean(),
garyservin 0:9e9b7db60fd5 56 period_stddev(),
garyservin 0:9e9b7db60fd5 57 period_max(),
garyservin 0:9e9b7db60fd5 58 stamp_age_mean(),
garyservin 0:9e9b7db60fd5 59 stamp_age_stddev(),
garyservin 0:9e9b7db60fd5 60 stamp_age_max()
garyservin 0:9e9b7db60fd5 61 {
garyservin 0:9e9b7db60fd5 62 }
garyservin 0:9e9b7db60fd5 63
garyservin 0:9e9b7db60fd5 64 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 65 {
garyservin 0:9e9b7db60fd5 66 int offset = 0;
garyservin 0:9e9b7db60fd5 67 uint32_t length_topic = strlen(this->topic);
garyservin 0:9e9b7db60fd5 68 varToArr(outbuffer + offset, length_topic);
garyservin 0:9e9b7db60fd5 69 offset += 4;
garyservin 0:9e9b7db60fd5 70 memcpy(outbuffer + offset, this->topic, length_topic);
garyservin 0:9e9b7db60fd5 71 offset += length_topic;
garyservin 0:9e9b7db60fd5 72 uint32_t length_node_pub = strlen(this->node_pub);
garyservin 0:9e9b7db60fd5 73 varToArr(outbuffer + offset, length_node_pub);
garyservin 0:9e9b7db60fd5 74 offset += 4;
garyservin 0:9e9b7db60fd5 75 memcpy(outbuffer + offset, this->node_pub, length_node_pub);
garyservin 0:9e9b7db60fd5 76 offset += length_node_pub;
garyservin 0:9e9b7db60fd5 77 uint32_t length_node_sub = strlen(this->node_sub);
garyservin 0:9e9b7db60fd5 78 varToArr(outbuffer + offset, length_node_sub);
garyservin 0:9e9b7db60fd5 79 offset += 4;
garyservin 0:9e9b7db60fd5 80 memcpy(outbuffer + offset, this->node_sub, length_node_sub);
garyservin 0:9e9b7db60fd5 81 offset += length_node_sub;
garyservin 0:9e9b7db60fd5 82 *(outbuffer + offset + 0) = (this->window_start.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 83 *(outbuffer + offset + 1) = (this->window_start.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 84 *(outbuffer + offset + 2) = (this->window_start.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 85 *(outbuffer + offset + 3) = (this->window_start.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 86 offset += sizeof(this->window_start.sec);
garyservin 0:9e9b7db60fd5 87 *(outbuffer + offset + 0) = (this->window_start.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 88 *(outbuffer + offset + 1) = (this->window_start.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 89 *(outbuffer + offset + 2) = (this->window_start.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 90 *(outbuffer + offset + 3) = (this->window_start.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 91 offset += sizeof(this->window_start.nsec);
garyservin 0:9e9b7db60fd5 92 *(outbuffer + offset + 0) = (this->window_stop.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 93 *(outbuffer + offset + 1) = (this->window_stop.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 94 *(outbuffer + offset + 2) = (this->window_stop.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 95 *(outbuffer + offset + 3) = (this->window_stop.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 96 offset += sizeof(this->window_stop.sec);
garyservin 0:9e9b7db60fd5 97 *(outbuffer + offset + 0) = (this->window_stop.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 98 *(outbuffer + offset + 1) = (this->window_stop.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 99 *(outbuffer + offset + 2) = (this->window_stop.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 100 *(outbuffer + offset + 3) = (this->window_stop.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 101 offset += sizeof(this->window_stop.nsec);
garyservin 0:9e9b7db60fd5 102 union {
garyservin 0:9e9b7db60fd5 103 int32_t real;
garyservin 0:9e9b7db60fd5 104 uint32_t base;
garyservin 0:9e9b7db60fd5 105 } u_delivered_msgs;
garyservin 0:9e9b7db60fd5 106 u_delivered_msgs.real = this->delivered_msgs;
garyservin 0:9e9b7db60fd5 107 *(outbuffer + offset + 0) = (u_delivered_msgs.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 108 *(outbuffer + offset + 1) = (u_delivered_msgs.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 109 *(outbuffer + offset + 2) = (u_delivered_msgs.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 110 *(outbuffer + offset + 3) = (u_delivered_msgs.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 111 offset += sizeof(this->delivered_msgs);
garyservin 0:9e9b7db60fd5 112 union {
garyservin 0:9e9b7db60fd5 113 int32_t real;
garyservin 0:9e9b7db60fd5 114 uint32_t base;
garyservin 0:9e9b7db60fd5 115 } u_dropped_msgs;
garyservin 0:9e9b7db60fd5 116 u_dropped_msgs.real = this->dropped_msgs;
garyservin 0:9e9b7db60fd5 117 *(outbuffer + offset + 0) = (u_dropped_msgs.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 118 *(outbuffer + offset + 1) = (u_dropped_msgs.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 119 *(outbuffer + offset + 2) = (u_dropped_msgs.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 120 *(outbuffer + offset + 3) = (u_dropped_msgs.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 121 offset += sizeof(this->dropped_msgs);
garyservin 0:9e9b7db60fd5 122 union {
garyservin 0:9e9b7db60fd5 123 int32_t real;
garyservin 0:9e9b7db60fd5 124 uint32_t base;
garyservin 0:9e9b7db60fd5 125 } u_traffic;
garyservin 0:9e9b7db60fd5 126 u_traffic.real = this->traffic;
garyservin 0:9e9b7db60fd5 127 *(outbuffer + offset + 0) = (u_traffic.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 128 *(outbuffer + offset + 1) = (u_traffic.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 129 *(outbuffer + offset + 2) = (u_traffic.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 130 *(outbuffer + offset + 3) = (u_traffic.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 131 offset += sizeof(this->traffic);
garyservin 0:9e9b7db60fd5 132 *(outbuffer + offset + 0) = (this->period_mean.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 133 *(outbuffer + offset + 1) = (this->period_mean.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 134 *(outbuffer + offset + 2) = (this->period_mean.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 135 *(outbuffer + offset + 3) = (this->period_mean.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 136 offset += sizeof(this->period_mean.sec);
garyservin 0:9e9b7db60fd5 137 *(outbuffer + offset + 0) = (this->period_mean.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 138 *(outbuffer + offset + 1) = (this->period_mean.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 139 *(outbuffer + offset + 2) = (this->period_mean.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 140 *(outbuffer + offset + 3) = (this->period_mean.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 141 offset += sizeof(this->period_mean.nsec);
garyservin 0:9e9b7db60fd5 142 *(outbuffer + offset + 0) = (this->period_stddev.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 143 *(outbuffer + offset + 1) = (this->period_stddev.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 144 *(outbuffer + offset + 2) = (this->period_stddev.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 145 *(outbuffer + offset + 3) = (this->period_stddev.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 146 offset += sizeof(this->period_stddev.sec);
garyservin 0:9e9b7db60fd5 147 *(outbuffer + offset + 0) = (this->period_stddev.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 148 *(outbuffer + offset + 1) = (this->period_stddev.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 149 *(outbuffer + offset + 2) = (this->period_stddev.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 150 *(outbuffer + offset + 3) = (this->period_stddev.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 151 offset += sizeof(this->period_stddev.nsec);
garyservin 0:9e9b7db60fd5 152 *(outbuffer + offset + 0) = (this->period_max.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 153 *(outbuffer + offset + 1) = (this->period_max.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 154 *(outbuffer + offset + 2) = (this->period_max.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 155 *(outbuffer + offset + 3) = (this->period_max.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 156 offset += sizeof(this->period_max.sec);
garyservin 0:9e9b7db60fd5 157 *(outbuffer + offset + 0) = (this->period_max.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 158 *(outbuffer + offset + 1) = (this->period_max.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 159 *(outbuffer + offset + 2) = (this->period_max.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 160 *(outbuffer + offset + 3) = (this->period_max.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 161 offset += sizeof(this->period_max.nsec);
garyservin 0:9e9b7db60fd5 162 *(outbuffer + offset + 0) = (this->stamp_age_mean.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 163 *(outbuffer + offset + 1) = (this->stamp_age_mean.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 164 *(outbuffer + offset + 2) = (this->stamp_age_mean.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 165 *(outbuffer + offset + 3) = (this->stamp_age_mean.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 166 offset += sizeof(this->stamp_age_mean.sec);
garyservin 0:9e9b7db60fd5 167 *(outbuffer + offset + 0) = (this->stamp_age_mean.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 168 *(outbuffer + offset + 1) = (this->stamp_age_mean.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 169 *(outbuffer + offset + 2) = (this->stamp_age_mean.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 170 *(outbuffer + offset + 3) = (this->stamp_age_mean.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 171 offset += sizeof(this->stamp_age_mean.nsec);
garyservin 0:9e9b7db60fd5 172 *(outbuffer + offset + 0) = (this->stamp_age_stddev.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 173 *(outbuffer + offset + 1) = (this->stamp_age_stddev.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 174 *(outbuffer + offset + 2) = (this->stamp_age_stddev.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 175 *(outbuffer + offset + 3) = (this->stamp_age_stddev.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 176 offset += sizeof(this->stamp_age_stddev.sec);
garyservin 0:9e9b7db60fd5 177 *(outbuffer + offset + 0) = (this->stamp_age_stddev.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 178 *(outbuffer + offset + 1) = (this->stamp_age_stddev.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 179 *(outbuffer + offset + 2) = (this->stamp_age_stddev.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 180 *(outbuffer + offset + 3) = (this->stamp_age_stddev.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 181 offset += sizeof(this->stamp_age_stddev.nsec);
garyservin 0:9e9b7db60fd5 182 *(outbuffer + offset + 0) = (this->stamp_age_max.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 183 *(outbuffer + offset + 1) = (this->stamp_age_max.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 184 *(outbuffer + offset + 2) = (this->stamp_age_max.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 185 *(outbuffer + offset + 3) = (this->stamp_age_max.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 186 offset += sizeof(this->stamp_age_max.sec);
garyservin 0:9e9b7db60fd5 187 *(outbuffer + offset + 0) = (this->stamp_age_max.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 188 *(outbuffer + offset + 1) = (this->stamp_age_max.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 189 *(outbuffer + offset + 2) = (this->stamp_age_max.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 190 *(outbuffer + offset + 3) = (this->stamp_age_max.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 191 offset += sizeof(this->stamp_age_max.nsec);
garyservin 0:9e9b7db60fd5 192 return offset;
garyservin 0:9e9b7db60fd5 193 }
garyservin 0:9e9b7db60fd5 194
garyservin 0:9e9b7db60fd5 195 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 196 {
garyservin 0:9e9b7db60fd5 197 int offset = 0;
garyservin 0:9e9b7db60fd5 198 uint32_t length_topic;
garyservin 0:9e9b7db60fd5 199 arrToVar(length_topic, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 200 offset += 4;
garyservin 0:9e9b7db60fd5 201 for(unsigned int k= offset; k< offset+length_topic; ++k){
garyservin 0:9e9b7db60fd5 202 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 203 }
garyservin 0:9e9b7db60fd5 204 inbuffer[offset+length_topic-1]=0;
garyservin 0:9e9b7db60fd5 205 this->topic = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 206 offset += length_topic;
garyservin 0:9e9b7db60fd5 207 uint32_t length_node_pub;
garyservin 0:9e9b7db60fd5 208 arrToVar(length_node_pub, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 209 offset += 4;
garyservin 0:9e9b7db60fd5 210 for(unsigned int k= offset; k< offset+length_node_pub; ++k){
garyservin 0:9e9b7db60fd5 211 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 212 }
garyservin 0:9e9b7db60fd5 213 inbuffer[offset+length_node_pub-1]=0;
garyservin 0:9e9b7db60fd5 214 this->node_pub = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 215 offset += length_node_pub;
garyservin 0:9e9b7db60fd5 216 uint32_t length_node_sub;
garyservin 0:9e9b7db60fd5 217 arrToVar(length_node_sub, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 218 offset += 4;
garyservin 0:9e9b7db60fd5 219 for(unsigned int k= offset; k< offset+length_node_sub; ++k){
garyservin 0:9e9b7db60fd5 220 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 221 }
garyservin 0:9e9b7db60fd5 222 inbuffer[offset+length_node_sub-1]=0;
garyservin 0:9e9b7db60fd5 223 this->node_sub = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 224 offset += length_node_sub;
garyservin 0:9e9b7db60fd5 225 this->window_start.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 226 this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 227 this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 228 this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 229 offset += sizeof(this->window_start.sec);
garyservin 0:9e9b7db60fd5 230 this->window_start.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 231 this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 232 this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 233 this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 234 offset += sizeof(this->window_start.nsec);
garyservin 0:9e9b7db60fd5 235 this->window_stop.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 236 this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 237 this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 238 this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 239 offset += sizeof(this->window_stop.sec);
garyservin 0:9e9b7db60fd5 240 this->window_stop.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 241 this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 242 this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 243 this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 244 offset += sizeof(this->window_stop.nsec);
garyservin 0:9e9b7db60fd5 245 union {
garyservin 0:9e9b7db60fd5 246 int32_t real;
garyservin 0:9e9b7db60fd5 247 uint32_t base;
garyservin 0:9e9b7db60fd5 248 } u_delivered_msgs;
garyservin 0:9e9b7db60fd5 249 u_delivered_msgs.base = 0;
garyservin 0:9e9b7db60fd5 250 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 251 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 252 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 253 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 254 this->delivered_msgs = u_delivered_msgs.real;
garyservin 0:9e9b7db60fd5 255 offset += sizeof(this->delivered_msgs);
garyservin 0:9e9b7db60fd5 256 union {
garyservin 0:9e9b7db60fd5 257 int32_t real;
garyservin 0:9e9b7db60fd5 258 uint32_t base;
garyservin 0:9e9b7db60fd5 259 } u_dropped_msgs;
garyservin 0:9e9b7db60fd5 260 u_dropped_msgs.base = 0;
garyservin 0:9e9b7db60fd5 261 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 262 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 263 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 264 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 265 this->dropped_msgs = u_dropped_msgs.real;
garyservin 0:9e9b7db60fd5 266 offset += sizeof(this->dropped_msgs);
garyservin 0:9e9b7db60fd5 267 union {
garyservin 0:9e9b7db60fd5 268 int32_t real;
garyservin 0:9e9b7db60fd5 269 uint32_t base;
garyservin 0:9e9b7db60fd5 270 } u_traffic;
garyservin 0:9e9b7db60fd5 271 u_traffic.base = 0;
garyservin 0:9e9b7db60fd5 272 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 273 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 274 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 275 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 276 this->traffic = u_traffic.real;
garyservin 0:9e9b7db60fd5 277 offset += sizeof(this->traffic);
garyservin 0:9e9b7db60fd5 278 this->period_mean.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 279 this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 280 this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 281 this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 282 offset += sizeof(this->period_mean.sec);
garyservin 0:9e9b7db60fd5 283 this->period_mean.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 284 this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 285 this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 286 this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 287 offset += sizeof(this->period_mean.nsec);
garyservin 0:9e9b7db60fd5 288 this->period_stddev.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 289 this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 290 this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 291 this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 292 offset += sizeof(this->period_stddev.sec);
garyservin 0:9e9b7db60fd5 293 this->period_stddev.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 294 this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 295 this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 296 this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 297 offset += sizeof(this->period_stddev.nsec);
garyservin 0:9e9b7db60fd5 298 this->period_max.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 299 this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 300 this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 301 this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 302 offset += sizeof(this->period_max.sec);
garyservin 0:9e9b7db60fd5 303 this->period_max.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 304 this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 305 this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 306 this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 307 offset += sizeof(this->period_max.nsec);
garyservin 0:9e9b7db60fd5 308 this->stamp_age_mean.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 309 this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 310 this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 311 this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 312 offset += sizeof(this->stamp_age_mean.sec);
garyservin 0:9e9b7db60fd5 313 this->stamp_age_mean.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 314 this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 315 this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 316 this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 317 offset += sizeof(this->stamp_age_mean.nsec);
garyservin 0:9e9b7db60fd5 318 this->stamp_age_stddev.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 319 this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 320 this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 321 this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 322 offset += sizeof(this->stamp_age_stddev.sec);
garyservin 0:9e9b7db60fd5 323 this->stamp_age_stddev.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 324 this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 325 this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 326 this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 327 offset += sizeof(this->stamp_age_stddev.nsec);
garyservin 0:9e9b7db60fd5 328 this->stamp_age_max.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 329 this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 330 this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 331 this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 332 offset += sizeof(this->stamp_age_max.sec);
garyservin 0:9e9b7db60fd5 333 this->stamp_age_max.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 334 this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 335 this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 336 this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 337 offset += sizeof(this->stamp_age_max.nsec);
garyservin 0:9e9b7db60fd5 338 return offset;
garyservin 0:9e9b7db60fd5 339 }
garyservin 0:9e9b7db60fd5 340
garyservin 0:9e9b7db60fd5 341 const char * getType(){ return "rosgraph_msgs/TopicStatistics"; };
garyservin 0:9e9b7db60fd5 342 const char * getMD5(){ return "10152ed868c5097a5e2e4a89d7daa710"; };
garyservin 0:9e9b7db60fd5 343
garyservin 0:9e9b7db60fd5 344 };
garyservin 0:9e9b7db60fd5 345
garyservin 0:9e9b7db60fd5 346 }
garyservin 0:9e9b7db60fd5 347 #endif