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

autogen lib 2021-06-02T22:02:24+02:00

parent 498c355d
No related branches found
No related tags found
No related merge requests found
......@@ -14,8 +14,8 @@ namespace mccd_msgs
public:
typedef uint8_t _status_type;
_status_type status;
enum { DISABLED = 0 };
enum { ENABLED = 1 };
enum { POWER_OFF = 0 };
enum { POWER_ON = 1 };
enum { OVERCURRENT = 2 };
enum { CMD_VEL_TIMEOUT = 3 };
......@@ -41,7 +41,7 @@ namespace mccd_msgs
}
virtual const char * getType() override { return "mccd_msgs/Status"; };
virtual const char * getMD5() override { return "bd45a5f976b4cf46caa9be680287a4d1"; };
virtual const char * getMD5() override { return "9171ac6345a40b8582e1dd7f29db42af"; };
};
......
......@@ -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