Skip to content

Commit 88dbc3e

Browse files
authored
Merge pull request #4 from BytesRobotics/master
Merge
2 parents c614bef + c0bc3f1 commit 88dbc3e

File tree

29 files changed

+693
-95
lines changed

29 files changed

+693
-95
lines changed

doc/parameters/param_list.md

+1
Original file line numberDiff line numberDiff line change
@@ -400,6 +400,7 @@ When `controller_plugins`\`progress_checker_plugin`\`goal_checker_plugin` parame
400400
| ----------| --------| ------------|
401401
| node_names | N/A | Ordered list of node names to bringup through lifecycle transition |
402402
| autostart | false | Whether to transition nodes to active state on startup |
403+
| bond_timeout_ms | 4000 | Timeout for bond to fail if no heartbeat can be found, in milliseconds. If set to 0, it will be disabled. Must be larger than 300ms for stable bringup. |
403404

404405
# map_server
405406

nav2_amcl/src/amcl_node.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -300,6 +300,9 @@ AmclNode::on_activate(const rclcpp_lifecycle::State & /*state*/)
300300
handleInitialPose(last_published_pose_);
301301
}
302302

303+
// create bond connection
304+
createBond();
305+
303306
return nav2_util::CallbackReturn::SUCCESS;
304307
}
305308

@@ -315,6 +318,9 @@ AmclNode::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
315318
particlecloud_pub_->on_deactivate();
316319
particle_cloud_pub_->on_deactivate();
317320

321+
// destroy bond connection
322+
destroyBond();
323+
318324
return nav2_util::CallbackReturn::SUCCESS;
319325
}
320326

nav2_bt_navigator/src/bt_navigator.cpp

+13-7
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
108108
get_node_clock_interface(),
109109
get_node_logging_interface(),
110110
get_node_waitables_interface(),
111-
"navigate_to_pose", std::bind(&BtNavigator::navigateToPose, this), false);
111+
"navigate_to_pose", std::bind(&BtNavigator::navigateToPose, this));
112112

113113
// Get the libraries to pull plugins from
114114
plugin_lib_names_ = get_parameter("plugin_lib_names").as_string_array();
@@ -133,11 +133,6 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
133133
// Get the BT filename to use from the node parameter
134134
get_parameter("default_bt_xml_filename", default_bt_xml_filename_);
135135

136-
if (!loadBehaviorTree(default_bt_xml_filename_)) {
137-
RCLCPP_ERROR(get_logger(), "Error loading XML file: %s", default_bt_xml_filename_.c_str());
138-
return nav2_util::CallbackReturn::FAILURE;
139-
}
140-
141136
return nav2_util::CallbackReturn::SUCCESS;
142137
}
143138

@@ -176,8 +171,16 @@ BtNavigator::on_activate(const rclcpp_lifecycle::State & /*state*/)
176171
{
177172
RCLCPP_INFO(get_logger(), "Activating");
178173

174+
if (!loadBehaviorTree(default_bt_xml_filename_)) {
175+
RCLCPP_ERROR(get_logger(), "Error loading XML file: %s", default_bt_xml_filename_.c_str());
176+
return nav2_util::CallbackReturn::FAILURE;
177+
}
178+
179179
action_server_->activate();
180180

181+
// create bond connection
182+
createBond();
183+
181184
return nav2_util::CallbackReturn::SUCCESS;
182185
}
183186

@@ -188,6 +191,9 @@ BtNavigator::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
188191

189192
action_server_->deactivate();
190193

194+
// destroy bond connection
195+
destroyBond();
196+
191197
return nav2_util::CallbackReturn::SUCCESS;
192198
}
193199

@@ -332,7 +338,7 @@ BtNavigator::initializeGoalPose()
332338
blackboard_->set<int>("number_recoveries", 0); // NOLINT
333339

334340
// Update the goal pose on the blackboard
335-
blackboard_->set("goal", goal->pose);
341+
blackboard_->set<geometry_msgs::msg::PoseStamped>("goal", goal->pose);
336342
}
337343

338344
void

nav2_controller/src/nav2_controller.cpp

+8
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
7272

7373
RCLCPP_INFO(get_logger(), "Configuring controller interface");
7474

75+
7576
get_parameter("progress_checker_plugin", progress_checker_id_);
7677
if (progress_checker_id_ == default_progress_checker_id_) {
7778
nav2_util::declare_parameter_if_not_declared(
@@ -93,6 +94,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
9394
rclcpp::ParameterValue(default_types_[i]));
9495
}
9596
}
97+
9698
controller_types_.resize(controller_ids_.size());
9799

98100
get_parameter("controller_frequency", controller_frequency_);
@@ -172,6 +174,9 @@ ControllerServer::on_activate(const rclcpp_lifecycle::State & state)
172174
vel_publisher_->on_activate();
173175
action_server_->activate();
174176

177+
// create bond connection
178+
createBond();
179+
175180
return nav2_util::CallbackReturn::SUCCESS;
176181
}
177182

@@ -190,6 +195,9 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & state)
190195
publishZeroVelocity();
191196
vel_publisher_->on_deactivate();
192197

198+
// destroy bond connection
199+
destroyBond();
200+
193201
return nav2_util::CallbackReturn::SUCCESS;
194202
}
195203

nav2_dwb_controller/nav_2d_utils/CMakeLists.txt

+10-2
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,15 @@ ament_target_dependencies(path_ops
4343
${dependencies}
4444
)
4545

46-
install(TARGETS conversions path_ops
46+
add_library(tf_help SHARED
47+
src/tf_help.cpp
48+
)
49+
50+
ament_target_dependencies(tf_help
51+
${dependencies}
52+
)
53+
54+
install(TARGETS conversions path_ops tf_help
4755
ARCHIVE DESTINATION lib
4856
LIBRARY DESTINATION lib
4957
RUNTIME DESTINATION bin
@@ -60,7 +68,7 @@ if(BUILD_TESTING)
6068
endif()
6169

6270
ament_export_include_directories(include)
63-
ament_export_libraries(conversions path_ops)
71+
ament_export_libraries(conversions path_ops tf_help)
6472
ament_export_dependencies(${dependencies})
6573

6674
ament_package()

nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/tf_help.hpp

+13-53
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737

3838
#include <string>
3939
#include <memory>
40+
#include "tf2_ros/buffer.h"
4041
#include "nav_2d_utils/conversions.hpp"
4142
#include "geometry_msgs/msg/pose_stamped.hpp"
4243
#include "nav_2d_msgs/msg/pose2_d_stamped.hpp"
@@ -55,46 +56,12 @@ namespace nav_2d_utils
5556
* @return True if successful transform
5657
*/
5758
bool transformPose(
58-
const std::shared_ptr<tf2_ros::Buffer> tf, const std::string frame,
59-
const geometry_msgs::msg::PoseStamped & in_pose, geometry_msgs::msg::PoseStamped & out_pose,
60-
rclcpp::Duration & transform_tolerance)
61-
{
62-
if (in_pose.header.frame_id == frame) {
63-
out_pose = in_pose;
64-
return true;
65-
}
66-
67-
try {
68-
tf->transform(in_pose, out_pose, frame);
69-
return true;
70-
} catch (tf2::ExtrapolationException & ex) {
71-
auto transform = tf->lookupTransform(frame, in_pose.header.frame_id, tf2::TimePointZero);
72-
if ((rclcpp::Time(in_pose.header.stamp) - rclcpp::Time(transform.header.stamp)) >
73-
transform_tolerance)
74-
{
75-
RCLCPP_ERROR(
76-
rclcpp::get_logger("tf_help"),
77-
"Transform data too old when converting from %s to %s",
78-
in_pose.header.frame_id.c_str(),
79-
frame.c_str());
80-
RCLCPP_ERROR(
81-
rclcpp::get_logger("tf_help"),
82-
"Data time: %ds %uns, Transform time: %ds %uns",
83-
in_pose.header.stamp.sec, in_pose.header.stamp.nanosec,
84-
transform.header.stamp.sec, transform.header.stamp.nanosec);
85-
return false;
86-
} else {
87-
tf2::doTransform(in_pose, out_pose, transform);
88-
return true;
89-
}
90-
} catch (tf2::TransformException & ex) {
91-
RCLCPP_ERROR(
92-
rclcpp::get_logger("tf_help"),
93-
"Exception in transformPose: %s", ex.what());
94-
return false;
95-
}
96-
return false;
97-
}
59+
const std::shared_ptr<tf2_ros::Buffer> tf,
60+
const std::string frame,
61+
const geometry_msgs::msg::PoseStamped & in_pose,
62+
geometry_msgs::msg::PoseStamped & out_pose,
63+
rclcpp::Duration & transform_tolerance
64+
);
9865

9966
/**
10067
* @brief Transform a Pose2DStamped from one frame to another while catching exceptions
@@ -107,19 +74,12 @@ bool transformPose(
10774
* @return True if successful transform
10875
*/
10976
bool transformPose(
110-
const std::shared_ptr<tf2_ros::Buffer> tf, const std::string frame,
111-
const nav_2d_msgs::msg::Pose2DStamped & in_pose, nav_2d_msgs::msg::Pose2DStamped & out_pose,
112-
rclcpp::Duration & transform_tolerance)
113-
{
114-
geometry_msgs::msg::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
115-
geometry_msgs::msg::PoseStamped out_3d_pose;
116-
117-
bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, transform_tolerance);
118-
if (ret) {
119-
out_pose = poseStampedToPose2D(out_3d_pose);
120-
}
121-
return ret;
122-
}
77+
const std::shared_ptr<tf2_ros::Buffer> tf,
78+
const std::string frame,
79+
const nav_2d_msgs::msg::Pose2DStamped & in_pose,
80+
nav_2d_msgs::msg::Pose2DStamped & out_pose,
81+
rclcpp::Duration & transform_tolerance
82+
);
12383

12484
} // namespace nav_2d_utils
12585

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,115 @@
1+
/*
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2017, Locus Robotics
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of the copyright holder nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*/
34+
35+
#include <memory>
36+
#include <string>
37+
#include "nav_2d_utils/tf_help.hpp"
38+
39+
namespace nav_2d_utils
40+
{
41+
42+
bool transformPose(
43+
const std::shared_ptr<tf2_ros::Buffer> tf,
44+
const std::string frame,
45+
const geometry_msgs::msg::PoseStamped & in_pose,
46+
geometry_msgs::msg::PoseStamped & out_pose,
47+
rclcpp::Duration & transform_tolerance
48+
)
49+
{
50+
if (in_pose.header.frame_id == frame) {
51+
out_pose = in_pose;
52+
return true;
53+
}
54+
55+
try {
56+
tf->transform(in_pose, out_pose, frame);
57+
return true;
58+
} catch (tf2::ExtrapolationException & ex) {
59+
auto transform = tf->lookupTransform(
60+
frame,
61+
in_pose.header.frame_id,
62+
tf2::TimePointZero
63+
);
64+
if (
65+
(rclcpp::Time(in_pose.header.stamp) - rclcpp::Time(transform.header.stamp)) >
66+
transform_tolerance)
67+
{
68+
RCLCPP_ERROR(
69+
rclcpp::get_logger("tf_help"),
70+
"Transform data too old when converting from %s to %s",
71+
in_pose.header.frame_id.c_str(),
72+
frame.c_str()
73+
);
74+
RCLCPP_ERROR(
75+
rclcpp::get_logger("tf_help"),
76+
"Data time: %ds %uns, Transform time: %ds %uns",
77+
in_pose.header.stamp.sec,
78+
in_pose.header.stamp.nanosec,
79+
transform.header.stamp.sec,
80+
transform.header.stamp.nanosec
81+
);
82+
return false;
83+
} else {
84+
tf2::doTransform(in_pose, out_pose, transform);
85+
return true;
86+
}
87+
} catch (tf2::TransformException & ex) {
88+
RCLCPP_ERROR(
89+
rclcpp::get_logger("tf_help"),
90+
"Exception in transformPose: %s",
91+
ex.what()
92+
);
93+
return false;
94+
}
95+
return false;
96+
}
97+
98+
bool transformPose(
99+
const std::shared_ptr<tf2_ros::Buffer> tf,
100+
const std::string frame,
101+
const nav_2d_msgs::msg::Pose2DStamped & in_pose,
102+
nav_2d_msgs::msg::Pose2DStamped & out_pose,
103+
rclcpp::Duration & transform_tolerance
104+
)
105+
{
106+
geometry_msgs::msg::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
107+
geometry_msgs::msg::PoseStamped out_3d_pose;
108+
109+
bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, transform_tolerance);
110+
if (ret) {
111+
out_pose = poseStampedToPose2D(out_3d_pose);
112+
}
113+
return ret;
114+
}
115+
} // namespace nav_2d_utils

nav2_lifecycle_manager/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ find_package(rclcpp REQUIRED)
1313
find_package(std_msgs REQUIRED)
1414
find_package(std_srvs REQUIRED)
1515
find_package(tf2_geometry_msgs REQUIRED)
16+
find_package(bondcpp REQUIRED)
1617

1718
nav2_package()
1819

@@ -38,6 +39,7 @@ set(dependencies
3839
std_msgs
3940
std_srvs
4041
tf2_geometry_msgs
42+
bondcpp
4143
)
4244

4345
ament_target_dependencies(${library_name}

0 commit comments

Comments
 (0)