Skip to content

Commit

Permalink
Metapackage + Reorg + build script updates (#107)
Browse files Browse the repository at this point in the history
* moved over
* moving all messages into an internal msgs metapackage grouping
* moving all the messages into a homologated package
* making necessary changes for the msgs package homologation
* adding metapackage
* adding  myself as a maintainer
* build script and doc updates for package in workspace
* dealing with merge issues
* remove author fields
* moving around
* merge conflict v3
* remove costmap 2d from utils
* killing src dir
* remove costmap 2d clone #3
* remove extraneous file
* kill dwa for some reason
* dwb rectification
* removing oregon author -> maintainer
* controller -> nav2_controller
* adding new msgs  to new things
* tags
* bringup pkg
* compiling with task status mode
* getting the task status to compile for dwa
* adding costmap2d into nav2 naming nominclature
* adding controller metapackage
* recursive definitions -- bringup cannot be inside of the metapackage
* kill bad line
* hopefully actual last git merge error...
* changelog resolve
  • Loading branch information
SteveMacenski authored and Michael Jeronimo committed Oct 10, 2018
1 parent 8a8b344 commit ac932ea
Show file tree
Hide file tree
Showing 387 changed files with 844 additions and 1,157 deletions.
14 changes: 7 additions & 7 deletions doc/BUILD.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ RUN apt-get install -y \
Third, ensure there are no ROS environment variables set in your terminal or `.bashrc` file before taking the steps below.*

```sh
mkdir <workspace_dir>
cd <workspace_dir>
mkdir <directory_for_workspaces>
cd <directory_for_workspaces>
wget https://raw.githubusercontent.com/ros-planning/navigation2/master/tools/initial_ros_setup.sh
chmod a+x initial_ros_setup.sh
./initial_ros_setup.sh
Expand All @@ -38,7 +38,7 @@ The `initial_ros_setup.sh` script downloads four ROS workspaces and then builds

* Navigation 2 - This repo.

After all the workspaces are downloaded, the `navigtion2/tools/build_all.sh` script is run which builds each repo in the order listed above using the `colcon build --symlink-install` command (except ROS 1 dependencies which are built using `catkin_make`)
After all the workspaces are downloaded, the `navigation2/tools/build_all.sh` script is run which builds each repo in the order listed above using the `colcon build --symlink-install` command (except ROS 1 dependencies which are built using `catkin_make`)

### Options

Expand All @@ -58,13 +58,13 @@ Most work will be done in the `navigation2` workspace, so just building that wil

To build just `navigation2`,
```sh
cd <workspace_dir>/navigation2
cd <directory_for_workspaces>/navigation2_ws
source ../navstack_dependencies_ws/install/setup.sh
colcon build --symlink-install
```

In the case that the developer changes any dependencies, they can run
`<workspace_dir>/navigation2/tools/build_all.sh` in a clean environment to get everything rebuilt easily
`<directory_for_workspaces>/navigation2_ws/src/navigation2/tools/build_all.sh` in a clean environment to get everything rebuilt easily

### Build System

Expand All @@ -75,9 +75,9 @@ Instead, it would be better to do an initial download of all the source and depe
./initial_ros_setup.sh --no-ros1 --download-only
```

Then the CI tool can monitor the `navigation2` repo, update it as necessary, and rebuild using either the `<workspace_dir>/navigation2/tools/build_all.sh` script or by running
Then the CI tool can monitor the `navigation2` repo, update it as necessary, and rebuild using either the `<directory_for_workspaces>/navigation2_ws/src/navigation2/tools/build_all.sh` script or by running
```sh
cd <workspace_dir>/navigation2
cd <directory_for_workspaces>/navigation2_ws/src/navigation2
source ../navstack_dependencies_ws/install/setup.sh
colcon build --symlink-install
```
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_tasks REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_planning_msgs REQUIRED)
find_package(nav2_msgs REQUIRED)

include_directories(
include
Expand All @@ -39,7 +39,7 @@ set(dependencies
nav2_tasks
task
nav2_util
nav2_planning_msgs
nav2_msgs
)

ament_target_dependencies(${executable_name}
Expand Down
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@
<build_depend>rclcpp</build_depend>
<build_depend>nav2_tasks</build_depend>
<build_depend>nav2_util</build_depend>
<build_depend>nav2_planning_msgs</build_depend>
<build_depend>nav2_msgs</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>nav2_tasks</exec_depend>
<exec_depend>nav2_planning_msgs</exec_depend>
<exec_depend>nav2_msgs</exec_depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
project(nav2_mission_execution_msgs)
project(nav2_bringup)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
Expand All @@ -12,15 +12,11 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"msg/MissionPlan.msg"
DEPENDENCIES builtin_interfaces geometry_msgs std_msgs
)
find_package(navigation2 REQUIRED)

ament_export_dependencies(rosidl_default_runtime)

install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})

ament_package()
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
11 changes: 5 additions & 6 deletions src/libs/nav2_libs_msgs/package.xml → nav2_bringup/package.xml
Original file line number Diff line number Diff line change
@@ -1,25 +1,24 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_libs_msgs</name>
<name>nav2_bringup</name>
<version>0.1.0</version>
<description>TODO</description>
<description>Bringup scripts and configurations for the navigation2 stack</description>
<maintainer email="michael.jeronimo@intel.com">Michael Jeronimo</maintainer>
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>rclcpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>navigation2</build_depend>
<build_depend>builtin_interfaces</build_depend>
<build_depend>rosidl_default_generators</build_depend>
<build_depend>geometry_msgs</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>builtin_interfaces</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>navigation2</exec_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav2_tasks REQUIRED)
find_package(nav2_planning_msgs REQUIRED)
find_package(nav2_msgs REQUIRED)

include_directories(
include
Expand All @@ -36,8 +36,8 @@ set(dependencies
rclcpp
std_msgs
nav2_tasks
nav2_planning_msgs
)
nav2_msgs
)

ament_target_dependencies(${executable_name}
${dependencies}
Expand Down
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <string>
#include <memory>
#include "nav2_tasks/task_status.hpp"
#include "nav2_tasks/navigate_to_pose_task.hpp"
#include "nav2_tasks/compute_path_to_pose_task.hpp"
#include "nav2_tasks/follow_path_task.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,11 @@

<build_depend>rclcpp</build_depend>
<build_depend>nav2_tasks</build_depend>
<build_depend>nav2_planning_msgs</build_depend>
<build_depend>nav2_msgs</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>nav2_tasks</exec_depend>
<exec_depend>nav2_planning_msgs</exec_depend>
<exec_depend>nav2_msgs</exec_depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(costmap_2d REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(rclcpp REQUIRED)
find_package(Boost REQUIRED COMPONENTS system thread)

Expand All @@ -27,7 +27,7 @@ add_library(${PROJECT_NAME}

set(dependencies
rclcpp
costmap_2d
nav2_costmap_2d
)

ament_target_dependencies(${PROJECT_NAME}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <vector>
#include <limits>
#include <memory>
#include "costmap_2d/costmap_2d.h"
#include "nav2_costmap_2d/costmap_2d.h"
#include "costmap_queue/map_based_queue.h"

namespace costmap_queue
Expand Down Expand Up @@ -113,7 +113,7 @@ class CostmapQueue : public MapBasedQueue<CellData>
* @param costmap Costmap which defines the size/number of cells
* @param manhattan If true, sort cells by Manhattan distance, otherwise use Euclidean distance
*/
explicit CostmapQueue(costmap_2d::Costmap2D & costmap, bool manhattan = false);
explicit CostmapQueue(nav2_costmap_2d::Costmap2D & costmap, bool manhattan = false);

/**
* @brief Clear the queue
Expand Down Expand Up @@ -162,7 +162,7 @@ class CostmapQueue : public MapBasedQueue<CellData>
*/
void computeCache();

costmap_2d::Costmap2D & costmap_;
nav2_costmap_2d::Costmap2D & costmap_;
std::vector<bool> seen_;
int max_distance_;
bool manhattan_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class LimitedCostmapQueue : public CostmapQueue
/**
* @brief Constructor with limit as an integer number of cells.
*/
LimitedCostmapQueue(costmap_2d::Costmap2D & costmap, const int cell_distance_limit);
LimitedCostmapQueue(nav2_costmap_2d::Costmap2D & costmap, const int cell_distance_limit);
bool validCellToQueue(const CellData & cell) override;
};
} // namespace costmap_queue
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<license>BSD</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<depend>costmap_2d</depend>
<depend>nav2_costmap_2d</depend>
<depend>rclcpp</depend>

<test_depend>ament_cmake_cppcheck</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ using std::hypot;
namespace costmap_queue
{

CostmapQueue::CostmapQueue(costmap_2d::Costmap2D & costmap, bool manhattan)
CostmapQueue::CostmapQueue(nav2_costmap_2d::Costmap2D & costmap, bool manhattan)
: MapBasedQueue(), costmap_(costmap), max_distance_(-1), manhattan_(manhattan),
cached_max_distance_(-1)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
namespace costmap_queue
{

LimitedCostmapQueue::LimitedCostmapQueue(costmap_2d::Costmap2D & costmap, const int distance_limit)
LimitedCostmapQueue::LimitedCostmapQueue(nav2_costmap_2d::Costmap2D & costmap, const int distance_limit)
: CostmapQueue(costmap)
{
max_distance_ = distance_limit;
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@

using std::hypot;

costmap_2d::Costmap2D costmap(5, 5, 1.0, 0.0, 0.0);
nav2_costmap_2d::Costmap2D costmap(5, 5, 1.0, 0.0, 0.0);

TEST(CostmapQueue, basicQueue)
{
Expand All @@ -59,7 +59,7 @@ TEST(CostmapQueue, basicQueue)

TEST(CostmapQueue, bigTest)
{
costmap_2d::Costmap2D big_map(500, 500, 1.0, 0.0, 0.0);
nav2_costmap_2d::Costmap2D big_map(500, 500, 1.0, 0.0, 0.0);
costmap_queue::CostmapQueue q(big_map);
int count = 0;
q.enqueueCell(0, 0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav_2d_msgs REQUIRED)
find_package(dwb_msgs REQUIRED)
find_package(costmap_2d REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(pluginlib REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
Expand All @@ -32,7 +32,7 @@ set(dependencies
geometry_msgs
nav_2d_msgs
dwb_msgs
costmap_2d
nav2_costmap_2d
pluginlib
sensor_msgs
visualization_msgs
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,15 @@
#define DWB_CORE__COMMON_TYPES_H_

#include <memory>
#include "costmap_2d/costmap_2d_ros.h"
#include "nav2_costmap_2d/costmap_2d_ros.h"
#include "tf2_ros/transform_listener.h"


namespace dwb_core
{

typedef std::shared_ptr<tf2_ros::Buffer> TFBufferPtr;
typedef std::shared_ptr<costmap_2d::Costmap2DROS> CostmapROSPtr;
typedef std::shared_ptr<nav2_costmap_2d::Costmap2DROS> CostmapROSPtr;

}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<build_depend>geometry_msgs</build_depend>
<build_depend>nav_2d_msgs</build_depend>
<build_depend>dwb_msgs</build_depend>
<build_depend>costmap_2d</build_depend>
<build_depend>nav2_costmap_2d</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>visualization_msgs</build_depend>
Expand All @@ -27,7 +27,7 @@
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>dwb_msgs</exec_depend>
<exec_depend>costmap_2d</exec_depend>
<exec_depend>nav2_costmap_2d</exec_depend>
<exec_depend>nav_2d_utils</exec_depend>
<exec_depend>pluginlib</exec_depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -393,7 +393,7 @@ nav_2d_msgs::msg::Path2D DWBLocalPlanner::transformGlobalPlan(
transformed_plan.header.stamp = pose.header.stamp;

// we'll discard points on the plan that are outside the local costmap
costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
double dist_threshold = std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY()) *
costmap->getResolution() / 2.0;
double sq_dist_threshold = dist_threshold * dist_threshold;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ void DWBPublisher::publishCostGrid(
cost_grid_pc.header.frame_id = costmap_ros->getGlobalFrameID();
cost_grid_pc.header.stamp = rclcpp::Clock().now();

costmap_2d::Costmap2D * costmap = costmap_ros->getCostmap();
nav2_costmap_2d::Costmap2D * costmap = costmap_ros->getCostmap();
double x_coord, y_coord;
unsigned int size_x = costmap->getSizeInCellsX();
unsigned int size_y = costmap->getSizeInCellsY();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(angles REQUIRED)
find_package(costmap_2d REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(costmap_queue REQUIRED)
find_package(dwb_core REQUIRED)
find_package(geometry_msgs REQUIRED)
Expand Down Expand Up @@ -43,7 +43,7 @@ add_library(${PROJECT_NAME}

set(dependencies
angles
costmap_2d
nav2_costmap_2d
costmap_queue
dwb_core
geometry_msgs
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class BaseObstacleCritic : public dwb_core::TrajectoryCritic
virtual bool isValidCost(const unsigned char cost);

protected:
costmap_2d::Costmap2D * costmap_;
nav2_costmap_2d::Costmap2D * costmap_;
bool sum_scores_;
};
} // namespace dwb_critics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ class MapGridCritic : public dwb_core::TrajectoryCritic
class MapGridQueue : public costmap_queue::CostmapQueue
{
public:
MapGridQueue(costmap_2d::Costmap2D & costmap, MapGridCritic & parent)
MapGridQueue(nav2_costmap_2d::Costmap2D & costmap, MapGridCritic & parent)
: costmap_queue::CostmapQueue(costmap, true), parent_(parent) {}
bool validCellToQueue(const costmap_queue::CellData & cell) override;

Expand All @@ -126,7 +126,7 @@ class MapGridCritic : public dwb_core::TrajectoryCritic
void propogateManhattanDistances();

std::shared_ptr<MapGridQueue> queue_;
costmap_2d::Costmap2D * costmap_;
nav2_costmap_2d::Costmap2D * costmap_;
std::vector<double> cell_values_;
double obstacle_score_, unreachable_score_; ///< Special cell_values
bool stop_on_failure_;
Expand Down

0 comments on commit ac932ea

Please sign in to comment.