add file nav_msgs
This commit is contained in:
28
nav_msgs/include/nav_msgs/GridCells.h
Normal file
28
nav_msgs/include/nav_msgs/GridCells.h
Normal file
@@ -0,0 +1,28 @@
|
||||
// #an array of cells in a 2D grid
|
||||
// Header header
|
||||
// float32 cell_width
|
||||
// float32 cell_height
|
||||
// geometry_msgs/Point[] cells
|
||||
#ifndef GRID_CELLS_H
|
||||
#define GRID_CELLS_H
|
||||
|
||||
#include <cstdint>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include "std_msgs/Header.h"
|
||||
#include "geometry_msgs/Point.h"
|
||||
|
||||
namespace nav_msgs
|
||||
{
|
||||
|
||||
struct GridCells
|
||||
{
|
||||
std_msgs::Header header;
|
||||
float cell_width;
|
||||
float cell_height;
|
||||
std::vector<geometry_msgs::Point> cells;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif //GRID_CELLS_H
|
||||
@@ -11,11 +11,11 @@ namespace nav_msgs
|
||||
|
||||
struct MapMetaData
|
||||
{
|
||||
double map_load_time;
|
||||
float resolution;
|
||||
uint32_t width;
|
||||
uint32_t height;
|
||||
geometry_msgs::Pose origin;
|
||||
double map_load_time;
|
||||
float resolution;
|
||||
uint32_t width;
|
||||
uint32_t height;
|
||||
geometry_msgs::Pose origin;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
32
nav_msgs/include/nav_msgs/Odometry.h
Normal file
32
nav_msgs/include/nav_msgs/Odometry.h
Normal file
@@ -0,0 +1,32 @@
|
||||
// # This represents an estimate of a position and velocity in free space.
|
||||
// # The pose in this message should be specified in the coordinate frame given by header.frame_id.
|
||||
// # The twist in this message should be specified in the coordinate frame given by the child_frame_id
|
||||
// Header header
|
||||
// string child_frame_id
|
||||
// geometry_msgs/PoseWithCovariance pose
|
||||
// geometry_msgs/TwistWithCovariance twist
|
||||
#ifndef ODOMETRY_H
|
||||
#define ODOMETRY_H
|
||||
|
||||
#include <cstdint>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include "std_msgs/Header.h"
|
||||
#include "geometry_msgs/Point.h"
|
||||
#include <geometry_msgs/PoseWithCovariance.h>
|
||||
#include <geometry_msgs/TwistWithCovariance.h>
|
||||
|
||||
namespace nav_msgs
|
||||
{
|
||||
|
||||
struct Odometry
|
||||
{
|
||||
std_msgs::Header header;
|
||||
std::string child_frame_id;
|
||||
geometry_msgs::PoseWithCovariance pose;
|
||||
geometry_msgs::TwistWithCovariance twist;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif //ODOMETRY_H
|
||||
25
nav_msgs/include/nav_msgs/Path.h
Normal file
25
nav_msgs/include/nav_msgs/Path.h
Normal file
@@ -0,0 +1,25 @@
|
||||
// #An array of poses that represents a Path for a robot to follow
|
||||
// Header header
|
||||
// geometry_msgs/PoseStamped[] poses
|
||||
#ifndef PATH_H
|
||||
#define PATH_H
|
||||
|
||||
#include <cstdint>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include "std_msgs/Header.h"
|
||||
#include "geometry_msgs/PoseStamped.h"
|
||||
|
||||
namespace nav_msgs
|
||||
{
|
||||
|
||||
struct Path
|
||||
{
|
||||
std_msgs::Header header;
|
||||
std::vector<geometry_msgs::PoseStamped> poses;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif //PATH_H
|
||||
|
||||
Reference in New Issue
Block a user