test

Dependencies:   mbed Watchdog

Dependents:   STM32-MC_node

Committer:
ommpy
Date:
Tue Jul 07 15:19:06 2020 +0530
Revision:
2:b7fdc74e5c5d
new board files

Who changed what in which revision?

UserRevisionLine numberNew contents of line
ommpy 2:b7fdc74e5c5d 1 #ifndef _ROS_gazebo_msgs_ContactsState_h
ommpy 2:b7fdc74e5c5d 2 #define _ROS_gazebo_msgs_ContactsState_h
ommpy 2:b7fdc74e5c5d 3
ommpy 2:b7fdc74e5c5d 4 #include <stdint.h>
ommpy 2:b7fdc74e5c5d 5 #include <string.h>
ommpy 2:b7fdc74e5c5d 6 #include <stdlib.h>
ommpy 2:b7fdc74e5c5d 7 #include "ros/msg.h"
ommpy 2:b7fdc74e5c5d 8 #include "std_msgs/Header.h"
ommpy 2:b7fdc74e5c5d 9 #include "gazebo_msgs/ContactState.h"
ommpy 2:b7fdc74e5c5d 10
ommpy 2:b7fdc74e5c5d 11 namespace gazebo_msgs
ommpy 2:b7fdc74e5c5d 12 {
ommpy 2:b7fdc74e5c5d 13
ommpy 2:b7fdc74e5c5d 14 class ContactsState : public ros::Msg
ommpy 2:b7fdc74e5c5d 15 {
ommpy 2:b7fdc74e5c5d 16 public:
ommpy 2:b7fdc74e5c5d 17 typedef std_msgs::Header _header_type;
ommpy 2:b7fdc74e5c5d 18 _header_type header;
ommpy 2:b7fdc74e5c5d 19 uint32_t states_length;
ommpy 2:b7fdc74e5c5d 20 typedef gazebo_msgs::ContactState _states_type;
ommpy 2:b7fdc74e5c5d 21 _states_type st_states;
ommpy 2:b7fdc74e5c5d 22 _states_type * states;
ommpy 2:b7fdc74e5c5d 23
ommpy 2:b7fdc74e5c5d 24 ContactsState():
ommpy 2:b7fdc74e5c5d 25 header(),
ommpy 2:b7fdc74e5c5d 26 states_length(0), states(NULL)
ommpy 2:b7fdc74e5c5d 27 {
ommpy 2:b7fdc74e5c5d 28 }
ommpy 2:b7fdc74e5c5d 29
ommpy 2:b7fdc74e5c5d 30 virtual int serialize(unsigned char *outbuffer) const
ommpy 2:b7fdc74e5c5d 31 {
ommpy 2:b7fdc74e5c5d 32 int offset = 0;
ommpy 2:b7fdc74e5c5d 33 offset += this->header.serialize(outbuffer + offset);
ommpy 2:b7fdc74e5c5d 34 *(outbuffer + offset + 0) = (this->states_length >> (8 * 0)) & 0xFF;
ommpy 2:b7fdc74e5c5d 35 *(outbuffer + offset + 1) = (this->states_length >> (8 * 1)) & 0xFF;
ommpy 2:b7fdc74e5c5d 36 *(outbuffer + offset + 2) = (this->states_length >> (8 * 2)) & 0xFF;
ommpy 2:b7fdc74e5c5d 37 *(outbuffer + offset + 3) = (this->states_length >> (8 * 3)) & 0xFF;
ommpy 2:b7fdc74e5c5d 38 offset += sizeof(this->states_length);
ommpy 2:b7fdc74e5c5d 39 for( uint32_t i = 0; i < states_length; i++){
ommpy 2:b7fdc74e5c5d 40 offset += this->states[i].serialize(outbuffer + offset);
ommpy 2:b7fdc74e5c5d 41 }
ommpy 2:b7fdc74e5c5d 42 return offset;
ommpy 2:b7fdc74e5c5d 43 }
ommpy 2:b7fdc74e5c5d 44
ommpy 2:b7fdc74e5c5d 45 virtual int deserialize(unsigned char *inbuffer)
ommpy 2:b7fdc74e5c5d 46 {
ommpy 2:b7fdc74e5c5d 47 int offset = 0;
ommpy 2:b7fdc74e5c5d 48 offset += this->header.deserialize(inbuffer + offset);
ommpy 2:b7fdc74e5c5d 49 uint32_t states_lengthT = ((uint32_t) (*(inbuffer + offset)));
ommpy 2:b7fdc74e5c5d 50 states_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
ommpy 2:b7fdc74e5c5d 51 states_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
ommpy 2:b7fdc74e5c5d 52 states_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
ommpy 2:b7fdc74e5c5d 53 offset += sizeof(this->states_length);
ommpy 2:b7fdc74e5c5d 54 if(states_lengthT > states_length)
ommpy 2:b7fdc74e5c5d 55 this->states = (gazebo_msgs::ContactState*)realloc(this->states, states_lengthT * sizeof(gazebo_msgs::ContactState));
ommpy 2:b7fdc74e5c5d 56 states_length = states_lengthT;
ommpy 2:b7fdc74e5c5d 57 for( uint32_t i = 0; i < states_length; i++){
ommpy 2:b7fdc74e5c5d 58 offset += this->st_states.deserialize(inbuffer + offset);
ommpy 2:b7fdc74e5c5d 59 memcpy( &(this->states[i]), &(this->st_states), sizeof(gazebo_msgs::ContactState));
ommpy 2:b7fdc74e5c5d 60 }
ommpy 2:b7fdc74e5c5d 61 return offset;
ommpy 2:b7fdc74e5c5d 62 }
ommpy 2:b7fdc74e5c5d 63
ommpy 2:b7fdc74e5c5d 64 const char * getType(){ return "gazebo_msgs/ContactsState"; };
ommpy 2:b7fdc74e5c5d 65 const char * getMD5(){ return "acbcb1601a8e525bf72509f18e6f668d"; };
ommpy 2:b7fdc74e5c5d 66
ommpy 2:b7fdc74e5c5d 67 };
ommpy 2:b7fdc74e5c5d 68
ommpy 2:b7fdc74e5c5d 69 }
ommpy 2:b7fdc74e5c5d 70 #endif