them file test static_layer
This commit is contained in:
@@ -25,7 +25,7 @@ struct MapLocation
|
||||
*/
|
||||
class Costmap2D
|
||||
{
|
||||
// friend class CostmapTester; // Cho phép lớp test (gtest) truy cập vào các thành viên private
|
||||
friend class CostmapTester; // Cho phép lớp test (gtest) truy cập vào các thành viên private
|
||||
public:
|
||||
/**
|
||||
* Constructor khởi tạo bản đồ costmap
|
||||
|
||||
@@ -146,5 +146,7 @@ private:
|
||||
double extra_min_x_, extra_max_x_, extra_min_y_, extra_max_y_;
|
||||
};
|
||||
|
||||
using PluginCostmapLayerPtr = std::shared_ptr<CostmapLayer>;
|
||||
|
||||
} // namespace costmap_2d
|
||||
#endif // COSTMAP_2D_COSTMAP_LAYER_H_
|
||||
|
||||
19
include/costmap_2d/critical_layer copy.h
Normal file
19
include/costmap_2d/critical_layer copy.h
Normal file
@@ -0,0 +1,19 @@
|
||||
#ifndef COSTMAP_2D_CRITICAL_LAYER_H_
|
||||
#define COSTMAP_2D_CRITICAL_LAYER_H_
|
||||
|
||||
#include <costmap_2d/static_layer.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
class CriticalLayer : public StaticLayer
|
||||
{
|
||||
public:
|
||||
CriticalLayer();
|
||||
virtual ~CriticalLayer();
|
||||
private:
|
||||
unsigned char interpretValue(unsigned char value);
|
||||
void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
|
||||
};
|
||||
}
|
||||
|
||||
#endif // COSTMAP_2D_CRITICAL_LAYER_H_
|
||||
100
include/costmap_2d/data_convert.h
Normal file
100
include/costmap_2d/data_convert.h
Normal file
@@ -0,0 +1,100 @@
|
||||
#ifndef DATA_CONVERT_H
|
||||
#define DATA_CONVERT_H
|
||||
|
||||
#include <geometry_msgs/TransformStamped.h>
|
||||
#include <tf2/utils.h>
|
||||
#include <tf2/compat.h>
|
||||
#include <robot/time.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
robot::Time convertTime(tf2::Time time)
|
||||
{
|
||||
robot::Time time_tmp;
|
||||
time_tmp.sec = time.sec;
|
||||
time_tmp.nsec = time.nsec;
|
||||
return time_tmp;
|
||||
}
|
||||
|
||||
tf2::Time convertTime(robot::Time time)
|
||||
{
|
||||
tf2::Time time_tmp;
|
||||
time_tmp.sec = time.sec;
|
||||
time_tmp.nsec = time.nsec;
|
||||
return time_tmp;
|
||||
}
|
||||
|
||||
|
||||
tf2::Transform convertToTf2Transform(const geometry_msgs::Transform& msg)
|
||||
{
|
||||
tf2::Quaternion q(
|
||||
msg.rotation.x,
|
||||
msg.rotation.y,
|
||||
msg.rotation.z,
|
||||
msg.rotation.w
|
||||
);
|
||||
|
||||
tf2::Vector3 t(
|
||||
msg.translation.x,
|
||||
msg.translation.y,
|
||||
msg.translation.z
|
||||
);
|
||||
|
||||
tf2::Transform tf(q, t);
|
||||
return tf;
|
||||
}
|
||||
|
||||
tf2::Transform convertToTf2Transform(const tf2::TransformMsg& msg)
|
||||
{
|
||||
tf2::Quaternion q(
|
||||
msg.rotation.x,
|
||||
msg.rotation.y,
|
||||
msg.rotation.z,
|
||||
msg.rotation.w
|
||||
);
|
||||
|
||||
tf2::Vector3 t(
|
||||
msg.translation.x,
|
||||
msg.translation.y,
|
||||
msg.translation.z
|
||||
);
|
||||
|
||||
tf2::Transform tf(q, t);
|
||||
return tf;
|
||||
}
|
||||
|
||||
tf2::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
|
||||
{
|
||||
tf2::TransformStampedMsg out;
|
||||
out.header.seq = msg.header.seq;
|
||||
out.header.stamp = convertTime(msg.header.stamp);
|
||||
out.header.frame_id = msg.header.frame_id;
|
||||
out.child_frame_id = msg.child_frame_id;
|
||||
out.transform.translation.x = msg.transform.translation.x;
|
||||
out.transform.translation.y = msg.transform.translation.y;
|
||||
out.transform.translation.z = msg.transform.translation.z;
|
||||
out.transform.rotation.x = msg.transform.rotation.x;
|
||||
out.transform.rotation.y = msg.transform.rotation.y;
|
||||
out.transform.rotation.z = msg.transform.rotation.z;
|
||||
out.transform.rotation.w = msg.transform.rotation.w;
|
||||
return out;
|
||||
}
|
||||
geometry_msgs::TransformStamped convertToTransformStamped(const tf2::TransformStampedMsg& msg)
|
||||
{
|
||||
geometry_msgs::TransformStamped out;
|
||||
out.header.seq = msg.header.seq;
|
||||
out.header.stamp = convertTime(msg.header.stamp);
|
||||
out.header.frame_id = msg.header.frame_id;
|
||||
out.child_frame_id = msg.child_frame_id;
|
||||
out.transform.translation.x = msg.transform.translation.x;
|
||||
out.transform.translation.y = msg.transform.translation.y;
|
||||
out.transform.translation.z = msg.transform.translation.z;
|
||||
out.transform.rotation.x = msg.transform.rotation.x;
|
||||
out.transform.rotation.y = msg.transform.rotation.y;
|
||||
out.transform.rotation.z = msg.transform.rotation.z;
|
||||
out.transform.rotation.w = msg.transform.rotation.w;
|
||||
return out;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // DATA_CONVERT_H
|
||||
37
include/costmap_2d/directional_layer.h
Normal file
37
include/costmap_2d/directional_layer.h
Normal file
@@ -0,0 +1,37 @@
|
||||
#ifndef COSTMAP_2D_DIRECTIONAL_LAYER_V1_H_
|
||||
#define COSTMAP_2D_DIRECTIONAL_LAYER_V1_H_
|
||||
|
||||
#include <costmap_2d/static_layer.h>
|
||||
// #include <tf/transform_listener.h>
|
||||
// #include <nav_msgs/Path.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
class DirectionalLayer : public StaticLayer
|
||||
{
|
||||
public:
|
||||
DirectionalLayer();
|
||||
virtual ~DirectionalLayer();
|
||||
// bool laneFilter(const std::vector<geometry_msgs::PoseStamped> plan);
|
||||
void resetMap();
|
||||
|
||||
private:
|
||||
// void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map);
|
||||
// bool laneFilter(std::vector<std::array<uint16_t, 2>> new_map, const nav_msgs::Path path);
|
||||
unsigned char laneFilter(unsigned int x, unsigned int y, double yaw_robot);
|
||||
// void laneFilter(std::vector<unsigned int> x, std::vector<unsigned int> y, std::vector<double> yaw_robot);
|
||||
void laneFilter(std::vector<std::pair<unsigned int, double>> x, std::vector<std::pair<unsigned int, double>> y, std::vector<double> yaw_robot);
|
||||
bool inSkipErea(double start_x, double start_y, double end_x, double end_y, double skip_distance);
|
||||
void convertToMap(unsigned char *costmap, nav_msgs::OccupancyGrid &dir_map, double occ_th, double free_th);
|
||||
bool getRobotPose(double &x, double &y, double &yaw);
|
||||
|
||||
std::vector<std::array<uint16_t, 2>> directional_areas_;
|
||||
double pose_x_, pose_y_, pose_yaw_;
|
||||
double distance_skip_ = 1.0;
|
||||
// ros::Publisher lane_mask_pub_;
|
||||
nav_msgs::OccupancyGrid new_map_;
|
||||
// tf::TransformListener listener_;
|
||||
};
|
||||
}
|
||||
|
||||
#endif // COSTMAP_2D_DIRECTIONAL_LAYER_H_
|
||||
@@ -41,7 +41,6 @@
|
||||
#include <geometry_msgs/Polygon.h>
|
||||
#include <geometry_msgs/PolygonStamped.h>
|
||||
|
||||
// #include<costmap_2d/msg.h>
|
||||
#include<string.h>
|
||||
#include<vector>
|
||||
|
||||
|
||||
@@ -5,10 +5,9 @@
|
||||
#include <costmap_2d/layer.h>
|
||||
#include <costmap_2d/layered_costmap.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include <boost/dll/alias.hpp>
|
||||
#include <stdexcept>
|
||||
#include <iostream>
|
||||
#include <yaml-cpp/yaml.h>
|
||||
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
|
||||
@@ -147,9 +147,6 @@ private:
|
||||
};
|
||||
|
||||
|
||||
using PluginPtr = std::shared_ptr<Layer>;
|
||||
|
||||
|
||||
} // namespace costmap_2d
|
||||
|
||||
#endif // COSTMAP_2D_LAYER_H_
|
||||
|
||||
@@ -1,85 +0,0 @@
|
||||
#ifndef COSTMAP_2D_COST_VALUES_H_MSG
|
||||
#define COSTMAP_2D_COST_VALUES_H_MSG
|
||||
/** Provides a mapping for often used cost values */
|
||||
#include<vector>
|
||||
#include<string>
|
||||
#include<chrono>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
struct Header
|
||||
{
|
||||
uint32_t seq;
|
||||
std::chrono::system_clock::time_point stamp;
|
||||
std::string frame_id;
|
||||
};
|
||||
|
||||
struct Point
|
||||
{
|
||||
double x;
|
||||
double y;
|
||||
double z;
|
||||
};
|
||||
|
||||
struct Point32
|
||||
{
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
};
|
||||
|
||||
struct PointStamped
|
||||
{
|
||||
Header header;
|
||||
Point point;
|
||||
};
|
||||
|
||||
struct Polygon
|
||||
{
|
||||
std::vector<Point32> points;
|
||||
};
|
||||
|
||||
struct PolygonStamped
|
||||
{
|
||||
// std_msgs/Header header; // Ignored for simplicity
|
||||
Polygon polygon;
|
||||
};
|
||||
|
||||
struct XmlRpcValue
|
||||
{
|
||||
std::vector<Point32> points;
|
||||
};
|
||||
|
||||
struct PointField
|
||||
{
|
||||
uint8_t INT8=1;
|
||||
uint8_t UINT8=2;
|
||||
uint8_t INT16=3;
|
||||
uint8_t UINT16=4;
|
||||
uint8_t INT32=5;
|
||||
uint8_t UINT32=6;
|
||||
uint8_t FLOAT32=7;
|
||||
uint8_t FLOAT64=8;
|
||||
std::string name;
|
||||
uint32_t offset;
|
||||
uint8_t datatype;
|
||||
uint32_t count;
|
||||
};
|
||||
|
||||
struct PointCloud2
|
||||
{
|
||||
Header header;
|
||||
uint32_t height;
|
||||
uint32_t width;
|
||||
std::vector<PointField> fields;
|
||||
bool is_bigendian;
|
||||
uint32_t point_step;
|
||||
uint32_t row_step;
|
||||
std::vector<uint8_t> data;
|
||||
bool is_dense;
|
||||
};
|
||||
|
||||
|
||||
|
||||
}
|
||||
#endif // COSTMAP_2D_COST_VALUES_H_MSG
|
||||
@@ -6,9 +6,8 @@
|
||||
#include <string>
|
||||
#include <chrono>
|
||||
// #include <ros/time.h>
|
||||
// #include <costmap_2d/observation.h>
|
||||
// #include <tf2/buffer_core.h>
|
||||
|
||||
#include <robot/time.h>
|
||||
#include <robot/duration.h>
|
||||
#include <costmap_2d/observation.h>
|
||||
#include <tf2/buffer_core.h>
|
||||
#include <sensor_msgs/PointCloud2.h>
|
||||
@@ -112,9 +111,9 @@ private:
|
||||
// const ros::Duration observation_keep_time_;
|
||||
// const ros::Duration expected_update_rate_;
|
||||
// ros::Time last_updated_;
|
||||
const std::chrono::duration<double> observation_keep_time_;
|
||||
const std::chrono::duration<double> expected_update_rate_;
|
||||
std::chrono::time_point<std::chrono::system_clock> last_updated_;
|
||||
const robot::Duration observation_keep_time_;
|
||||
const robot::Duration expected_update_rate_;
|
||||
robot::Time last_updated_;
|
||||
std::string global_frame_;
|
||||
std::string sensor_frame_;
|
||||
std::list<Observation> observation_list_;
|
||||
|
||||
@@ -41,19 +41,19 @@
|
||||
#include <costmap_2d/costmap_layer.h>
|
||||
#include <costmap_2d/layered_costmap.h>
|
||||
#include <costmap_2d/observation_buffer.h>
|
||||
#include <costmap_2d/footprint.h>
|
||||
#include <costmap_2d/utils.h>
|
||||
|
||||
#include <nav_msgs/OccupancyGrid.h>
|
||||
|
||||
#include <sensor_msgs/LaserScan.h>
|
||||
// #include <laser_geometry/laser_geometry.h>
|
||||
#include <sensor_msgs/PointCloud.h>
|
||||
#include <sensor_msgs/PointCloud2.h>
|
||||
#include <sensor_msgs/point_cloud_conversion.h>
|
||||
|
||||
// #include <laser_geometry/laser_geometry.h>
|
||||
// #include <tf2_ros/message_filter.h>
|
||||
// #include <message_filters/subscriber.h>
|
||||
// #include <dynamic_reconfigure/server.h>
|
||||
// #include <costmap_2d/ObstaclePluginConfig.h>
|
||||
#include <costmap_2d/footprint.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
|
||||
18
include/costmap_2d/preferred_layer.h
Normal file
18
include/costmap_2d/preferred_layer.h
Normal file
@@ -0,0 +1,18 @@
|
||||
#ifndef COSTMAP_2D_PREFERRED_LAYER_H_
|
||||
#define COSTMAP_2D_PREFERRED_LAYER_H_
|
||||
|
||||
#include <costmap_2d/static_layer.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
class PreferredLayer : public StaticLayer
|
||||
{
|
||||
public:
|
||||
PreferredLayer();
|
||||
virtual ~PreferredLayer();
|
||||
private:
|
||||
unsigned char interpretValue(unsigned char value);
|
||||
};
|
||||
}
|
||||
|
||||
#endif // COSTMAP_2D_PREFERRED_LAYER_
|
||||
@@ -3,8 +3,6 @@
|
||||
|
||||
#include <costmap_2d/costmap_layer.h>
|
||||
#include <costmap_2d/layered_costmap.h>
|
||||
// #include <costmap_2d/GenericPluginConfig.h>
|
||||
// #include <dynamic_reconfigure/server.h>
|
||||
#include <nav_msgs/OccupancyGrid.h>
|
||||
#include <map_msgs/OccupancyGridUpdate.h>
|
||||
// #include <message_filters/subscriber.h>
|
||||
@@ -46,6 +44,8 @@ protected:
|
||||
bool use_maximum_;
|
||||
bool first_map_only_; ///< @brief Store the first static map and reuse it on reinitializing
|
||||
bool trinary_costmap_;
|
||||
bool map_shutdown_ = false;
|
||||
bool map_update_shutdown_ = false;
|
||||
// ros::Subscriber map_sub_, map_update_sub_;
|
||||
unsigned char lethal_threshold_, unknown_cost_value_;
|
||||
|
||||
@@ -58,6 +58,7 @@ private:
|
||||
*/
|
||||
// void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level);
|
||||
// dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig> *dsrv_;
|
||||
bool getParams();
|
||||
};
|
||||
|
||||
} // namespace costmap_2d
|
||||
|
||||
99
include/costmap_2d/testing_helper.h
Normal file
99
include/costmap_2d/testing_helper.h
Normal file
@@ -0,0 +1,99 @@
|
||||
#ifndef COSTMAP_2D_TESTING_HELPER_H
|
||||
#define COSTMAP_2D_TESTING_HELPER_H
|
||||
|
||||
#include<costmap_2d/cost_values.h>
|
||||
#include<costmap_2d/costmap_2d.h>
|
||||
#include <costmap_2d/static_layer.h>
|
||||
#include <costmap_2d/obstacle_layer.h>
|
||||
#include <costmap_2d/inflation_layer.h>
|
||||
|
||||
#include <sensor_msgs/point_cloud2_iterator.h>
|
||||
|
||||
const double MAX_Z(1.0);
|
||||
|
||||
char printableCost(unsigned char cost)
|
||||
{
|
||||
switch (cost)
|
||||
{
|
||||
case costmap_2d::NO_INFORMATION: return '?';
|
||||
case costmap_2d::LETHAL_OBSTACLE: return 'L';
|
||||
case costmap_2d::INSCRIBED_INFLATED_OBSTACLE: return 'I';
|
||||
case costmap_2d::FREE_SPACE: return '.';
|
||||
default: return '0' + (unsigned char) (10 * cost / 255);
|
||||
}
|
||||
}
|
||||
|
||||
void printMap(costmap_2d::Costmap2D& costmap)
|
||||
{
|
||||
printf("map:\n");
|
||||
for (int i = 0; i < costmap.getSizeInCellsY(); i++){
|
||||
for (int j = 0; j < costmap.getSizeInCellsX(); j++){
|
||||
printf("%4d", int(costmap.getCost(j, i)));
|
||||
}
|
||||
printf("\n\n");
|
||||
}
|
||||
}
|
||||
|
||||
unsigned int countValues(costmap_2d::Costmap2D& costmap, unsigned char value, bool equal = true)
|
||||
{
|
||||
unsigned int count = 0;
|
||||
for (int i = 0; i < costmap.getSizeInCellsY(); i++){
|
||||
for (int j = 0; j < costmap.getSizeInCellsX(); j++){
|
||||
unsigned char c = costmap.getCost(j, i);
|
||||
if ((equal && c == value) || (!equal && c != value))
|
||||
{
|
||||
count+=1;
|
||||
}
|
||||
}
|
||||
}
|
||||
return count;
|
||||
}
|
||||
|
||||
void addStaticLayer(costmap_2d::LayeredCostmap& layers, tf2_ros::Buffer& tf)
|
||||
{
|
||||
costmap_2d::StaticLayer* slayer = new costmap_2d::StaticLayer();
|
||||
layers.addPlugin(boost::shared_ptr<costmap_2d::Layer>(slayer));
|
||||
slayer->initialize(&layers, "static", &tf);
|
||||
}
|
||||
|
||||
costmap_2d::ObstacleLayer* addObstacleLayer(costmap_2d::LayeredCostmap& layers, tf2_ros::Buffer& tf)
|
||||
{
|
||||
costmap_2d::ObstacleLayer* olayer = new costmap_2d::ObstacleLayer();
|
||||
olayer->initialize(&layers, "obstacles", &tf);
|
||||
layers.addPlugin(boost::shared_ptr<costmap_2d::Layer>(olayer));
|
||||
return olayer;
|
||||
}
|
||||
|
||||
void addObservation(costmap_2d::ObstacleLayer* olayer, double x, double y, double z = 0.0,
|
||||
double ox = 0.0, double oy = 0.0, double oz = MAX_Z){
|
||||
sensor_msgs::PointCloud2 cloud;
|
||||
sensor_msgs::PointCloud2Modifier modifier(cloud);
|
||||
modifier.setPointCloud2FieldsByString(1, "xyz");
|
||||
modifier.resize(1);
|
||||
sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
|
||||
sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
|
||||
sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
|
||||
*iter_x = x;
|
||||
*iter_y = y;
|
||||
*iter_z = z;
|
||||
|
||||
geometry_msgs::Point p;
|
||||
p.x = ox;
|
||||
p.y = oy;
|
||||
p.z = oz;
|
||||
|
||||
costmap_2d::Observation obs(p, cloud, 100.0, 100.0); // obstacle range = raytrace range = 100.0
|
||||
olayer->addStaticObservation(obs, true, true);
|
||||
}
|
||||
|
||||
costmap_2d::InflationLayer* addInflationLayer(costmap_2d::LayeredCostmap& layers, tf2_ros::Buffer& tf)
|
||||
{
|
||||
costmap_2d::InflationLayer* ilayer = new costmap_2d::InflationLayer();
|
||||
ilayer->initialize(&layers, "inflation", &tf);
|
||||
boost::shared_ptr<costmap_2d::Layer> ipointer(ilayer);
|
||||
layers.addPlugin(ipointer);
|
||||
return ilayer;
|
||||
}
|
||||
|
||||
|
||||
#endif // COSTMAP_2D_TESTING_HELPER_H
|
||||
21
include/costmap_2d/unpreferred_layer.h
Normal file
21
include/costmap_2d/unpreferred_layer.h
Normal file
@@ -0,0 +1,21 @@
|
||||
#ifndef COSTMAP_2D_UNPREFERRED_LAYER_H_
|
||||
#define COSTMAP_2D_UNPREFERRED_LAYER_H_
|
||||
|
||||
#include <costmap_2d/static_layer.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
class UnPreferredLayer : public StaticLayer
|
||||
{
|
||||
public:
|
||||
UnPreferredLayer();
|
||||
virtual ~UnPreferredLayer();
|
||||
|
||||
private:
|
||||
unsigned char interpretValue(unsigned char value);
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // COSTMAP_2D_UNPREFERRED_LAYER_
|
||||
17
include/costmap_2d/utils.h
Normal file
17
include/costmap_2d/utils.h
Normal file
@@ -0,0 +1,17 @@
|
||||
#ifndef COSTMAP_2D_UTILS_H
|
||||
#define COSTMAP_2D_UTILS_H
|
||||
#include <yaml-cpp/yaml.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
template<typename T>
|
||||
T loadParam(const YAML::Node& node, const std::string& key, const T& default_value)
|
||||
{
|
||||
if (node[key] && node[key].IsDefined())
|
||||
return node[key].as<T>();
|
||||
return default_value;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif // COSTMAP_2D_UTILS_H
|
||||
30
include/costmap_2d/voxel_grid.h
Normal file
30
include/costmap_2d/voxel_grid.h
Normal file
@@ -0,0 +1,30 @@
|
||||
// Header header
|
||||
// uint32_t[] data
|
||||
// geometry_msgs/Point32 origin
|
||||
// geometry_msgs/Vector3 resolutions
|
||||
// uint32_t size_x
|
||||
// uint32_t size_y
|
||||
// uint32_t size_z
|
||||
#ifndef COSTMAP_2D_VOXEL_GRID_H_
|
||||
#define COSTMAP_2D_VOXEL_GRID_H_
|
||||
|
||||
#include <std_msgs/Header.h>
|
||||
#include <geometry_msgs/Point32.h>
|
||||
#include <geometry_msgs/Vector3.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
struct VoxelGrid
|
||||
{
|
||||
std_msgs::Header header;
|
||||
std::vector<uint32_t> data;
|
||||
geometry_msgs::Point32 origin;
|
||||
geometry_msgs::Vector3 resolutions;
|
||||
uint32_t size_x;
|
||||
uint32_t size_y;
|
||||
uint32_t size_z;
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
#endif // COSTMAP_2D_VOXEL_GRID_H_
|
||||
149
include/costmap_2d/voxel_layer.h
Normal file
149
include/costmap_2d/voxel_layer.h
Normal file
@@ -0,0 +1,149 @@
|
||||
/*********************************************************************
|
||||
*
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, 2013, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* Author: Eitan Marder-Eppstein
|
||||
* David V. Lu!!
|
||||
*********************************************************************/
|
||||
#ifndef COSTMAP_2D_VOXEL_LAYER_H_
|
||||
#define COSTMAP_2D_VOXEL_LAYER_H_
|
||||
|
||||
// #include <ros/ros.h>
|
||||
#include <costmap_2d/layer.h>
|
||||
#include <costmap_2d/layered_costmap.h>
|
||||
#include <costmap_2d/observation_buffer.h>
|
||||
#include <costmap_2d/voxel_grid.h>
|
||||
#include <nav_msgs/OccupancyGrid.h>
|
||||
#include <sensor_msgs/LaserScan.h>
|
||||
// #include <laser_geometry/laser_geometry.h>
|
||||
#include <sensor_msgs/PointCloud.h>
|
||||
#include <sensor_msgs/PointCloud2.h>
|
||||
#include <sensor_msgs/point_cloud_conversion.h>
|
||||
// #include <message_filters/subscriber.h>
|
||||
// #include <dynamic_reconfigure/server.h>
|
||||
// #include <costmap_2d/VoxelPluginConfig.h>
|
||||
#include <costmap_2d/obstacle_layer.h>
|
||||
// #include <voxel_grid/voxel_grid.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
|
||||
class VoxelLayer : public ObstacleLayer
|
||||
{
|
||||
public:
|
||||
VoxelLayer() //: voxel_grid_(0, 0, 0)
|
||||
{
|
||||
costmap_ = NULL; // this is the unsigned char* member of parent class's parent class Costmap2D.
|
||||
}
|
||||
|
||||
virtual ~VoxelLayer();
|
||||
|
||||
virtual void onInitialize();
|
||||
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
|
||||
double* max_x, double* max_y);
|
||||
|
||||
void updateOrigin(double new_origin_x, double new_origin_y);
|
||||
bool isDiscretized()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
virtual void matchSize();
|
||||
virtual void reset();
|
||||
|
||||
|
||||
protected:
|
||||
// virtual void setupDynamicReconfigure(ros::NodeHandle& nh);
|
||||
|
||||
virtual void resetMaps();
|
||||
|
||||
private:
|
||||
// void reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level);
|
||||
void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info);
|
||||
virtual void raytraceFreespace(const costmap_2d::Observation& clearing_observation, double* min_x, double* min_y,
|
||||
double* max_x, double* max_y);
|
||||
|
||||
// dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig> *voxel_dsrv_;
|
||||
|
||||
bool publish_voxel_;
|
||||
// ros::Publisher voxel_pub_;
|
||||
// voxel_grid::VoxelGrid voxel_grid_;
|
||||
double z_resolution_, origin_z_;
|
||||
unsigned int unknown_threshold_, mark_threshold_, size_z_;
|
||||
// ros::Publisher clearing_endpoints_pub_;
|
||||
sensor_msgs::PointCloud clearing_endpoints_;
|
||||
|
||||
inline bool worldToMap3DFloat(double wx, double wy, double wz, double& mx, double& my, double& mz)
|
||||
{
|
||||
if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
|
||||
return false;
|
||||
mx = ((wx - origin_x_) / resolution_);
|
||||
my = ((wy - origin_y_) / resolution_);
|
||||
mz = ((wz - origin_z_) / z_resolution_);
|
||||
if (mx < size_x_ && my < size_y_ && mz < size_z_)
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
inline bool worldToMap3D(double wx, double wy, double wz, unsigned int& mx, unsigned int& my, unsigned int& mz)
|
||||
{
|
||||
if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
|
||||
return false;
|
||||
|
||||
mx = (int)((wx - origin_x_) / resolution_);
|
||||
my = (int)((wy - origin_y_) / resolution_);
|
||||
mz = (int)((wz - origin_z_) / z_resolution_);
|
||||
|
||||
if (mx < size_x_ && my < size_y_ && mz < size_z_)
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
inline void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double& wx, double& wy, double& wz)
|
||||
{
|
||||
// returns the center point of the cell
|
||||
wx = origin_x_ + (mx + 0.5) * resolution_;
|
||||
wy = origin_y_ + (my + 0.5) * resolution_;
|
||||
wz = origin_z_ + (mz + 0.5) * z_resolution_;
|
||||
}
|
||||
|
||||
inline double dist(double x0, double y0, double z0, double x1, double y1, double z1)
|
||||
{
|
||||
return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace costmap_2d
|
||||
|
||||
#endif // COSTMAP_2D_VOXEL_LAYER_H_
|
||||
Reference in New Issue
Block a user