Skip to content
This repository was archived by the owner on Dec 1, 2020. It is now read-only.
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
79 changes: 79 additions & 0 deletions lib/ros_lib/march_shared_resources/Alive.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
#ifndef _ROS_march_shared_resources_Alive_h
#define _ROS_march_shared_resources_Alive_h

#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"
#include "ros/time.h"

namespace march_shared_resources
{

class Alive : public ros::Msg
{
public:
typedef ros::Time _stamp_type;
_stamp_type stamp;
typedef const char* _id_type;
_id_type id;

Alive():
stamp(),
id("")
{
}

virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
*(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF;
*(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF;
*(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF;
*(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF;
offset += sizeof(this->stamp.sec);
*(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF;
*(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF;
*(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF;
*(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF;
offset += sizeof(this->stamp.nsec);
uint32_t length_id = strlen(this->id);
varToArr(outbuffer + offset, length_id);
offset += 4;
memcpy(outbuffer + offset, this->id, length_id);
offset += length_id;
return offset;
}

virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
this->stamp.sec = ((uint32_t) (*(inbuffer + offset)));
this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
offset += sizeof(this->stamp.sec);
this->stamp.nsec = ((uint32_t) (*(inbuffer + offset)));
this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
offset += sizeof(this->stamp.nsec);
uint32_t length_id;
arrToVar(length_id, (inbuffer + offset));
offset += 4;
for(unsigned int k= offset; k< offset+length_id; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_id-1]=0;
this->id = (char *)(inbuffer + offset-1);
offset += length_id;
return offset;
}

const char * getType(){ return "march_shared_resources/Alive"; };
const char * getMD5(){ return "302881f31927c1df708a2dbab0e80ee8"; };

};

}
#endif
142 changes: 142 additions & 0 deletions lib/ros_lib/march_shared_resources/ContainsGait.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
#ifndef _ROS_SERVICE_ContainsGait_h
#define _ROS_SERVICE_ContainsGait_h
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"

namespace march_shared_resources
{

static const char CONTAINSGAIT[] = "march_shared_resources/ContainsGait";

class ContainsGaitRequest : public ros::Msg
{
public:
typedef const char* _gait_type;
_gait_type gait;
uint32_t subgaits_length;
typedef char* _subgaits_type;
_subgaits_type st_subgaits;
_subgaits_type * subgaits;

ContainsGaitRequest():
gait(""),
subgaits_length(0), subgaits(NULL)
{
}

virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
uint32_t length_gait = strlen(this->gait);
varToArr(outbuffer + offset, length_gait);
offset += 4;
memcpy(outbuffer + offset, this->gait, length_gait);
offset += length_gait;
*(outbuffer + offset + 0) = (this->subgaits_length >> (8 * 0)) & 0xFF;
*(outbuffer + offset + 1) = (this->subgaits_length >> (8 * 1)) & 0xFF;
*(outbuffer + offset + 2) = (this->subgaits_length >> (8 * 2)) & 0xFF;
*(outbuffer + offset + 3) = (this->subgaits_length >> (8 * 3)) & 0xFF;
offset += sizeof(this->subgaits_length);
for( uint32_t i = 0; i < subgaits_length; i++){
uint32_t length_subgaitsi = strlen(this->subgaits[i]);
varToArr(outbuffer + offset, length_subgaitsi);
offset += 4;
memcpy(outbuffer + offset, this->subgaits[i], length_subgaitsi);
offset += length_subgaitsi;
}
return offset;
}

virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
uint32_t length_gait;
arrToVar(length_gait, (inbuffer + offset));
offset += 4;
for(unsigned int k= offset; k< offset+length_gait; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_gait-1]=0;
this->gait = (char *)(inbuffer + offset-1);
offset += length_gait;
uint32_t subgaits_lengthT = ((uint32_t) (*(inbuffer + offset)));
subgaits_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
subgaits_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
subgaits_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
offset += sizeof(this->subgaits_length);
if(subgaits_lengthT > subgaits_length)
this->subgaits = (char**)realloc(this->subgaits, subgaits_lengthT * sizeof(char*));
subgaits_length = subgaits_lengthT;
for( uint32_t i = 0; i < subgaits_length; i++){
uint32_t length_st_subgaits;
arrToVar(length_st_subgaits, (inbuffer + offset));
offset += 4;
for(unsigned int k= offset; k< offset+length_st_subgaits; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_st_subgaits-1]=0;
this->st_subgaits = (char *)(inbuffer + offset-1);
offset += length_st_subgaits;
memcpy( &(this->subgaits[i]), &(this->st_subgaits), sizeof(char*));
}
return offset;
}

const char * getType(){ return CONTAINSGAIT; };
const char * getMD5(){ return "c234d34b1f77b3f85ab7f59d681e4aab"; };

};

class ContainsGaitResponse : public ros::Msg
{
public:
typedef bool _contains_type;
_contains_type contains;

ContainsGaitResponse():
contains(0)
{
}

virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
union {
bool real;
uint8_t base;
} u_contains;
u_contains.real = this->contains;
*(outbuffer + offset + 0) = (u_contains.base >> (8 * 0)) & 0xFF;
offset += sizeof(this->contains);
return offset;
}

virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
union {
bool real;
uint8_t base;
} u_contains;
u_contains.base = 0;
u_contains.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
this->contains = u_contains.real;
offset += sizeof(this->contains);
return offset;
}

const char * getType(){ return CONTAINSGAIT; };
const char * getMD5(){ return "5865510046ec078baae5a62527defb32"; };

};

class ContainsGait {
public:
typedef ContainsGaitRequest Request;
typedef ContainsGaitResponse Response;
};

}
#endif
136 changes: 136 additions & 0 deletions lib/ros_lib/march_shared_resources/CurrentGait.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
#ifndef _ROS_march_shared_resources_CurrentGait_h
#define _ROS_march_shared_resources_CurrentGait_h

#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"
#include "std_msgs/Header.h"
#include "ros/duration.h"

namespace march_shared_resources
{

class CurrentGait : public ros::Msg
{
public:
typedef std_msgs::Header _header_type;
_header_type header;
typedef const char* _gait_type;
_gait_type gait;
typedef const char* _subgait_type;
_subgait_type subgait;
typedef const char* _version_type;
_version_type version;
typedef ros::Duration _duration_type;
_duration_type duration;
typedef const char* _gait_type_type;
_gait_type_type gait_type;

CurrentGait():
header(),
gait(""),
subgait(""),
version(""),
duration(),
gait_type("")
{
}

virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
offset += this->header.serialize(outbuffer + offset);
uint32_t length_gait = strlen(this->gait);
varToArr(outbuffer + offset, length_gait);
offset += 4;
memcpy(outbuffer + offset, this->gait, length_gait);
offset += length_gait;
uint32_t length_subgait = strlen(this->subgait);
varToArr(outbuffer + offset, length_subgait);
offset += 4;
memcpy(outbuffer + offset, this->subgait, length_subgait);
offset += length_subgait;
uint32_t length_version = strlen(this->version);
varToArr(outbuffer + offset, length_version);
offset += 4;
memcpy(outbuffer + offset, this->version, length_version);
offset += length_version;
*(outbuffer + offset + 0) = (this->duration.sec >> (8 * 0)) & 0xFF;
*(outbuffer + offset + 1) = (this->duration.sec >> (8 * 1)) & 0xFF;
*(outbuffer + offset + 2) = (this->duration.sec >> (8 * 2)) & 0xFF;
*(outbuffer + offset + 3) = (this->duration.sec >> (8 * 3)) & 0xFF;
offset += sizeof(this->duration.sec);
*(outbuffer + offset + 0) = (this->duration.nsec >> (8 * 0)) & 0xFF;
*(outbuffer + offset + 1) = (this->duration.nsec >> (8 * 1)) & 0xFF;
*(outbuffer + offset + 2) = (this->duration.nsec >> (8 * 2)) & 0xFF;
*(outbuffer + offset + 3) = (this->duration.nsec >> (8 * 3)) & 0xFF;
offset += sizeof(this->duration.nsec);
uint32_t length_gait_type = strlen(this->gait_type);
varToArr(outbuffer + offset, length_gait_type);
offset += 4;
memcpy(outbuffer + offset, this->gait_type, length_gait_type);
offset += length_gait_type;
return offset;
}

virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
offset += this->header.deserialize(inbuffer + offset);
uint32_t length_gait;
arrToVar(length_gait, (inbuffer + offset));
offset += 4;
for(unsigned int k= offset; k< offset+length_gait; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_gait-1]=0;
this->gait = (char *)(inbuffer + offset-1);
offset += length_gait;
uint32_t length_subgait;
arrToVar(length_subgait, (inbuffer + offset));
offset += 4;
for(unsigned int k= offset; k< offset+length_subgait; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_subgait-1]=0;
this->subgait = (char *)(inbuffer + offset-1);
offset += length_subgait;
uint32_t length_version;
arrToVar(length_version, (inbuffer + offset));
offset += 4;
for(unsigned int k= offset; k< offset+length_version; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_version-1]=0;
this->version = (char *)(inbuffer + offset-1);
offset += length_version;
this->duration.sec = ((uint32_t) (*(inbuffer + offset)));
this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
offset += sizeof(this->duration.sec);
this->duration.nsec = ((uint32_t) (*(inbuffer + offset)));
this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
offset += sizeof(this->duration.nsec);
uint32_t length_gait_type;
arrToVar(length_gait_type, (inbuffer + offset));
offset += 4;
for(unsigned int k= offset; k< offset+length_gait_type; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_gait_type-1]=0;
this->gait_type = (char *)(inbuffer + offset-1);
offset += length_gait_type;
return offset;
}

const char * getType(){ return "march_shared_resources/CurrentGait"; };
const char * getMD5(){ return "05545223cf87f9c70c68a04b825e8621"; };

};

}
#endif
Loading