Skip to content

Commit

Permalink
Merge nav2 humble to master_umd
Browse files Browse the repository at this point in the history
  • Loading branch information
vicmassy committed Aug 5, 2022
1 parent efb400b commit bc64d48
Show file tree
Hide file tree
Showing 10 changed files with 15 additions and 31 deletions.
12 changes: 6 additions & 6 deletions debian/create_debians.sh
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ rosdep update &> /dev/null
# Package list to create and install debian.
# Watch out the order to avoid missing dependencies while creating the debian.
PACKAGE_LIST_UNDERLAY=(
BehaviorTree.CPP \
angles/angles
BehaviorTree/BehaviorTree.CPP \
ros/angles/angles
)

for PACKAGE in ${PACKAGE_LIST_UNDERLAY[@]}; do
Expand All @@ -21,8 +21,8 @@ for PACKAGE in ${PACKAGE_LIST_UNDERLAY[@]}; do

# We have to go to the ROS package parent directory
cd /opt/underlay_ws/src/$PACKAGE;
bloom-generate rosdebian --ros-distro foxy &> /dev/null
debian/rules "binary --parallel" &> /dev/null
bloom-generate rosdebian --ros-distro humble
debian/rules "binary --parallel --with autoreconf "

cd ..
DEB_FILE=$(find *.deb);
Expand Down Expand Up @@ -62,8 +62,8 @@ for PACKAGE in ${PACKAGE_LIST[@]}; do

# We have to go to the ROS package parent directory
cd $PACKAGE;
bloom-generate rosdebian --ros-distro foxy &> /dev/null
debian/rules "binary --parallel" &> /dev/null
bloom-generate rosdebian --ros-distro humble
debian/rules "binary --parallel --with autoreconf "

cd ..
DEB_FILE=$(find *.deb);
Expand Down
10 changes: 0 additions & 10 deletions nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,16 +71,6 @@ if(BUILD_TESTING)
add_subdirectory(plugins/test)
endif()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
set(ament_cmake_copyright_FOUND TRUE)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
add_subdirectory(plugins/test)
endif()

ament_target_dependencies(${executable_name}
${dependencies}
)
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -536,7 +536,7 @@ void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped &
{
// Updated(Sergi): We need TwistStamped instead of Twist because Copter HAL uses frames for TF
if (vel_publisher_->is_activated() && vel_publisher_->get_subscription_count() > 0) {
vel_publisher_->publish(std::move(cmd_vel));
vel_publisher_->publish(velocity);
}
}

Expand Down
1 change: 0 additions & 1 deletion nav2_costmap_2d/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nav2_common</build_depend>

<depend>angles</depend>
<depend>geometry_msgs</depend>
<depend>laser_geometry</depend>
<depend>map_msgs</depend>
Expand Down
2 changes: 0 additions & 2 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,8 +326,6 @@ Costmap2DROS::getParameters()

auto node = shared_from_this();

auto node = shared_from_this();

if (plugin_names_ == default_plugins_) {
for (size_t i = 0; i < default_plugins_.size(); ++i) {
nav2_util::declare_parameter_if_not_declared(
Expand Down
8 changes: 3 additions & 5 deletions nav2_minimal.dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
# docker build -t nav2:latest \
# --build-arg UNDERLAY_MIXINS \
# --build-arg OVERLAY_MIXINS ./
ARG FROM_IMAGE=ros:foxy-ros-base
ARG FROM_IMAGE=ros:humble-ros-base

# multi-stage for caching
FROM $FROM_IMAGE AS cache
Expand Down Expand Up @@ -109,13 +109,11 @@ ENV OVERLAY_WS /opt/overlay_ws
WORKDIR $OVERLAY_WS/src

COPY debian/create_debians.sh $OVERLAY_WS/src/create_debians.sh
# COPY umd_mission/docker/debian/50-my-packages.list /etc/ros/rosdep/sources.list.d/50-my-packages.list
# COPY umd_mission/docker/debian/rosdep.yaml /rosdep.yaml

RUN . /opt/ros/foxy/setup.sh \
RUN . /opt/ros/humble/setup.sh \
&& . /opt/overlay_ws/install/setup.sh \
&& . /opt/underlay_ws/install/setup.sh \
&& ./create_debians.sh \
&& rm -rf $OVERLAY_WS $UNDERLAY_WS

WORKDIR /opt/ros/foxy
WORKDIR /opt/ros/humble
2 changes: 1 addition & 1 deletion nav2_navfn_planner/src/navfn_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ namespace nav2_navfn_planner
if (!makePlan(start.pose, goal.poses[0].pose, tolerance_, path))
{
RCLCPP_WARN(
node_->get_logger(), "%s: failed to create plan with "
logger_, "%s: failed to create plan with "
"tolerance %.2f.",
name_.c_str(), tolerance_);
}
Expand Down
1 change: 0 additions & 1 deletion nav2_planner/include/nav2_planner/planner_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,6 @@ class PlannerServer : public nav2_util::LifecycleNode

// Our action server implements the ComputePath action
std::unique_ptr<ActionServer> action_server_;
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;

/**
* @brief Check if an action server is valid / active
Expand Down
2 changes: 1 addition & 1 deletion nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State &state)

// Create the action server that we implement with our navigateToPose method
action_server_ = std::make_unique<ActionServer>(
rclcpp_node_,
node,
"compute_path_to_pose",
std::bind(&PlannerServer::computePlan, this));

Expand Down
6 changes: 3 additions & 3 deletions tools/ros2_minimal_dependencies.repos
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
repositories:
BehaviorTree.CPP:
BehaviorTree/BehaviorTree.CPP:
type: git
url: https://github.com/BehaviorTree/BehaviorTree.CPP.git
version: 3.5.3
angles:
version: master
ros/angles:
type: git
url: https://github.com/ros/angles.git
version: ros2

0 comments on commit bc64d48

Please sign in to comment.