Skip to content
Snippets Groups Projects
Unverified Commit 3aad4d16 authored by Michael Jeronimo's avatar Michael Jeronimo Committed by GitHub
Browse files

Rename the costmap_world_model (#268)

* Rename the costmap_world_model
* Remove placeholder .gitignore files

The original idea was that we might have different world model implementations. However, as it turns out, we will likely only have the one implementation that evolves over time. So, we don't necessarily want to emphasize that it is costmap-based, but want to allow for other representations going forward. Hence the name change.
parent 6d37648c
No related branches found
No related tags found
No related merge requests found
cmake_minimum_required(VERSION 3.5)
project(nav2_costmap_world_model)
project(nav2_world_model)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
......@@ -20,7 +20,7 @@ include_directories(
include
)
set(executable_name costmap_world_model)
set(executable_name world_model)
add_executable(${executable_name}
src/main.cpp
......@@ -29,7 +29,7 @@ add_executable(${executable_name}
set(library_name ${executable_name}_core)
add_library(${library_name}
src/costmap_world_model.cpp
src/world_model.cpp
)
set(dependencies
......
File moved
......@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_COSTMAP_WORLD_MODEL__COSTMAP_WORLD_MODEL_HPP_
#define NAV2_COSTMAP_WORLD_MODEL__COSTMAP_WORLD_MODEL_HPP_
#ifndef NAV2_WORLD_MODEL__WORLD_MODEL_HPP_
#define NAV2_WORLD_MODEL__WORLD_MODEL_HPP_
#include <string>
#include <vector>
......@@ -28,14 +28,14 @@
#include "nav2_msgs/srv/get_costmap.hpp"
#include "tf2_ros/transform_listener.h"
namespace nav2_costmap_world_model
namespace nav2_world_model
{
class CostmapWorldModel : public rclcpp::Node
class WorldModel : public rclcpp::Node
{
public:
explicit CostmapWorldModel(const std::string & name);
CostmapWorldModel();
explicit WorldModel(const std::string & name);
WorldModel();
template<class LayerT>
void addLayer(std::string layer_name)
......@@ -60,6 +60,6 @@ private:
rclcpp::Node::SharedPtr node_;
};
} // namespace nav2_costmap_world_model
} // namespace nav2_world_model
#endif // NAV2_COSTMAP_WORLD_MODEL__COSTMAP_WORLD_MODEL_HPP_
#endif // NAV2_WORLD_MODEL__WORLD_MODEL_HPP_
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_costmap_world_model</name>
<name>nav2_world_model</name>
<version>0.1.0</version>
<description>TODO</description>
<maintainer email="brian.wilcox@intel.com">Brian Wilcox</maintainer>
......
......@@ -14,12 +14,12 @@
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "nav2_costmap_world_model/costmap_world_model.hpp"
#include "nav2_world_model/world_model.hpp"
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<nav2_costmap_world_model::CostmapWorldModel>());
rclcpp::spin(std::make_shared<nav2_world_model::WorldModel>());
rclcpp::shutdown();
return 0;
......
......@@ -17,15 +17,15 @@
#include <vector>
#include <string>
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "nav2_costmap_world_model/costmap_world_model.hpp"
#include "nav2_world_model/world_model.hpp"
using std::vector;
using std::string;
namespace nav2_costmap_world_model
namespace nav2_world_model
{
CostmapWorldModel::CostmapWorldModel(const string & name)
WorldModel::WorldModel(const string & name)
: Node(name + "_Node")
{
node_ = std::shared_ptr<rclcpp::Node>(this, [](rclcpp::Node *) {});
......@@ -40,11 +40,11 @@ CostmapWorldModel::CostmapWorldModel(const string & name)
// Create a service that will use the callback function to handle requests.
costmapServer_ = create_service<nav2_msgs::srv::GetCostmap>(name + "_GetCostmap",
std::bind(&CostmapWorldModel::costmap_callback, this,
std::bind(&WorldModel::costmap_callback, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
}
void CostmapWorldModel::costmap_callback(
void WorldModel::costmap_callback(
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>/*request*/,
const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response)
......@@ -78,7 +78,7 @@ void CostmapWorldModel::costmap_callback(
response->map.data.assign(data, data + data_length);
}
void CostmapWorldModel::setFootprint(double length, double width)
void WorldModel::setFootprint(double length, double width)
{
std::vector<geometry_msgs::msg::Point> polygon;
geometry_msgs::msg::Point p;
......@@ -97,9 +97,9 @@ void CostmapWorldModel::setFootprint(double length, double width)
layered_costmap_->setFootprint(polygon);
}
CostmapWorldModel::CostmapWorldModel()
: CostmapWorldModel("WorldModel")
WorldModel::WorldModel()
: WorldModel("WorldModel")
{
}
} // namespace nav2_costmap_world_model
} // namespace nav2_world_model
......@@ -16,7 +16,7 @@
<depend>nav2_astar_planner</depend>
<depend>nav2_bt_navigator</depend>
<depend>nav2_costmap_2d</depend>
<depend>nav2_costmap_world_model</depend>
<depend>nav2_world_model</depend>
<depend>nav2_dijkstra_planner</depend>
<depend>nav2_gazebo_localizer</depend>
<depend>nav2_map_server</depend>
......
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