Skip to content
Snippets Groups Projects
Commit c1593429 authored by Compiler bot's avatar Compiler bot
Browse files

autogen lib 2021-07-04T16:44:21+00:00

parent 06d5bf47
No related branches found
No related tags found
No related merge requests found
......@@ -13,32 +13,32 @@ static const char SETSERVOPOSITION[] = "multiclamp_srvs/SetServoPosition";
class SetServoPositionRequest : public ros::Msg
{
public:
typedef uint8_t _servo_pos_type;
_servo_pos_type servo_pos;
typedef uint8_t _servos_pos_type;
_servos_pos_type servos_pos;
SetServoPositionRequest():
servo_pos(0)
servos_pos(0)
{
}
virtual int serialize(unsigned char *outbuffer) const override
{
int offset = 0;
*(outbuffer + offset + 0) = (this->servo_pos >> (8 * 0)) & 0xFF;
offset += sizeof(this->servo_pos);
*(outbuffer + offset + 0) = (this->servos_pos >> (8 * 0)) & 0xFF;
offset += sizeof(this->servos_pos);
return offset;
}
virtual int deserialize(unsigned char *inbuffer) override
{
int offset = 0;
this->servo_pos = ((uint8_t) (*(inbuffer + offset)));
offset += sizeof(this->servo_pos);
this->servos_pos = ((uint8_t) (*(inbuffer + offset)));
offset += sizeof(this->servos_pos);
return offset;
}
virtual const char * getType() override { return SETSERVOPOSITION; };
virtual const char * getMD5() override { return "d21a32ee6c54f246397c82ff6da8ffa6"; };
virtual const char * getMD5() override { return "9d8b987b5b9c3aae5efa6688877f214c"; };
};
......
......@@ -4,8 +4,8 @@
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "nav_msgs/OccupancyGrid.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
namespace nav_msgs
{
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment