Skip to content

Commit

Permalink
Fix Jazzy release by removing boost dependency - bump to 1.3.1 (#4492) (
Browse files Browse the repository at this point in the history
#4493)

* Update package.xml

Signed-off-by: Steve Macenski <[email protected]>

* fix Boost build issues and bump to 1.3.1 for jazzy release

---------

Signed-off-by: Steve Macenski <[email protected]>
(cherry picked from commit 715df8f)

Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
mergify[bot] and SteveMacenski authored Jun 25, 2024
1 parent 3a5d5c2 commit ad4e84b
Show file tree
Hide file tree
Showing 44 changed files with 46 additions and 47 deletions.
2 changes: 1 addition & 1 deletion nav2_amcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_amcl</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>
<p>
amcl is a probabilistic localization system for a robot moving in
Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_behavior_tree</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Nav2 behavior tree wrappers, nodes, and utilities</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
Expand Down
5 changes: 2 additions & 3 deletions nav2_behavior_tree/src/generate_nav2_tree_nodes_xml.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,21 +15,20 @@
#include <vector>
#include <string>
#include <fstream>
#include <boost/algorithm/string.hpp>

#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp/bt_factory.h"
#include "behaviortree_cpp/utils/shared_library.h"
#include "behaviortree_cpp/xml_parsing.h"

#include "plugins_list.hpp"
#include "nav2_util/string_utils.hpp"

int main()
{
BT::BehaviorTreeFactory factory;

std::vector<std::string> plugins_list;
boost::split(plugins_list, nav2::details::BT_BUILTIN_PLUGINS, boost::is_any_of(";"));
std::vector<std::string> plugins_list = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS, ';');

for (const auto & plugin : plugins_list) {
std::cout << "Loading: " << plugin << "\n";
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_behaviors</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Nav2 behavior server</description>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_bringup</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Bringup scripts and configurations for the Nav2 stack</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_bt_navigator</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Nav2 BT Navigator Server</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<license>Apache-2.0</license>
Expand Down
4 changes: 2 additions & 2 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,10 @@
#include <string>
#include <utility>
#include <vector>
#include <boost/algorithm/string.hpp>

#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/string_utils.hpp"
#include "nav2_util/robot_utils.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

Expand Down Expand Up @@ -74,7 +74,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)

// Libraries to pull plugins (BT Nodes) from
std::vector<std::string> plugin_lib_names;
boost::split(plugin_lib_names, nav2::details::BT_BUILTIN_PLUGINS, boost::is_any_of(";"));
plugin_lib_names = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS, ';');

auto user_defined_plugins = get_parameter("plugin_lib_names").as_string_array();
// append user_defined_plugins to plugin_lib_names
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_collision_monitor</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Collision Monitor</description>
<maintainer email="[email protected]">Alexey Merzlyakov</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_common</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Common support functionality used throughout the navigation 2 stack</description>
<maintainer email="[email protected]">Carl Delsey</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_constrained_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_constrained_smoother</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Ceres constrained smoother</description>
<maintainer email="[email protected]">Matej Vargovcik</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_controller</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Controller action interface</description>
<maintainer email="[email protected]">Carl Delsey</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_core</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>A set of headers for plugins core to the Nav2 stack</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<maintainer email="[email protected]">Carl Delsey</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format ="3">
<name>nav2_costmap_2d</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>
This package provides an implementation of a 2D costmap that takes in sensor
data from the world, builds a 2D or 3D occupancy grid of the data (depending
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>opennav_docking</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>A Task Server for robot charger docking</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking_bt/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>opennav_docking_bt</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>A set of BT nodes and XMLs for docking</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>opennav_docking_core</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>A set of headers for plugins core to the opennav docking framework</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/costmap_queue/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>costmap_queue</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>The costmap_queue package</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>dwb_core</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>DWB core interfaces package</description>
<maintainer email="[email protected]">Carl Delsey</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_critics/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>dwb_critics</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>The dwb_critics package</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>dwb_msgs</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Message/Service definitions specifically for the dwb_core</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_plugins/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>dwb_plugins</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>
Standard implementations of the GoalChecker
and TrajectoryGenerators for dwb_core
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav2_dwb_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_dwb_controller</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>
ROS2 controller (DWB) metapackage
</description>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav_2d_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav_2d_msgs</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Basic message types for two dimensional navigation, extending from geometry_msgs::Pose2D.</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav_2d_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav_2d_utils</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>A handful of useful utility functions for nav_2d packages.</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_graceful_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_graceful_controller</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Graceful motion controller</description>
<maintainer email="[email protected]">Alberto Tudela</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_lifecycle_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_lifecycle_manager</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>A controller/manager for the lifecycle nodes of the Navigation 2 system</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_map_server</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>
Refactored map server for ROS2 Navigation
</description>
Expand Down
2 changes: 1 addition & 1 deletion nav2_mppi_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_mppi_controller</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>nav2_mppi_controller</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<maintainer email="[email protected]">Aleksei Budyakov</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_msgs</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Messages and service files for the Nav2 stack</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_navfn_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_navfn_planner</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Nav2 NavFn planner</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_planner</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Nav2 planner server package</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_regulated_pure_pursuit_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_regulated_pure_pursuit_controller</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Regulated Pure Pursuit Controller</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<maintainer email="[email protected]">Shrijit Singh</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_rotation_shim_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_rotation_shim_controller</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Rotation Shim Controller</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_rviz_plugins/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_rviz_plugins</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Navigation 2 plugins for rviz</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_simple_commander/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_simple_commander</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>An importable library for writing mobile robot applications in python3</description>
<maintainer email="[email protected]">steve</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_smac_planner</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Smac global planning plugin: A*, Hybrid-A*, State Lattice</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_smoother</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Smoother action interface</description>
<maintainer email="[email protected]">Matej Vargovcik</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_system_tests/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_system_tests</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>A sets of system-level tests for Nav2 usually involving full robot simulation</description>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_theta_star_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_theta_star_planner</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Theta* Global Planning Plugin</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<maintainer email="[email protected]">Anshumaan Singh</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_util/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_util</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Nav2 utilities</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Mohammad Haghighipanah</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_velocity_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_velocity_smoother</name>
<version>1.3.0</version>
<version>1.3.1</version>
<description>Nav2's Output velocity smoother</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>
Expand Down
Loading

0 comments on commit ad4e84b

Please sign in to comment.