Skip to content

Commit f37457e

Browse files
committed
Bunches of random new tests (#1909)
* trying to get A* to work again * make flake 8 happy * adding cancel and preempt test * planner tests use A* * adding A* note * test with topic
1 parent a28de80 commit f37457e

File tree

8 files changed

+46
-23
lines changed

8 files changed

+46
-23
lines changed

nav2_planner/src/planner_server.cpp

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -66,10 +66,7 @@ PlannerServer::PlannerServer()
6666
PlannerServer::~PlannerServer()
6767
{
6868
RCLCPP_INFO(get_logger(), "Destroying");
69-
PlannerMap::iterator it;
70-
for (it = planners_.begin(); it != planners_.end(); ++it) {
71-
it->second.reset();
72-
}
69+
planners_.clear();
7370
}
7471

7572
nav2_util::CallbackReturn

nav2_system_tests/src/planning/planner_tester.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,10 @@ void PlannerTester::activate()
6767
// The navfn wrapper
6868
auto state = rclcpp_lifecycle::State();
6969
planner_tester_ = std::make_shared<NavFnPlannerTester>();
70+
planner_tester_->declare_parameter(
71+
"GridBased.use_astar", rclcpp::ParameterValue(true));
72+
planner_tester_->set_parameter(
73+
rclcpp::Parameter(std::string("GridBased.use_astar"), rclcpp::ParameterValue(true)));
7074
planner_tester_->onConfigure(state);
7175
publishRobotTransform();
7276
map_pub_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map", 1);

nav2_system_tests/src/system/CMakeLists.txt

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,6 @@
1+
# NOTE: The ASTAR=True does not work currently due to remapping not functioning
2+
# All set to false, A* testing of NavFn happens in the planning test portion
3+
14
ament_add_test(test_bt_navigator
25
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
36
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_launch.py"
@@ -9,7 +12,7 @@ ament_add_test(test_bt_navigator
912
TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo.world
1013
GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
1114
BT_NAVIGATOR_XML=navigate_w_replanning_and_recovery.xml
12-
ASTAR=True
15+
ASTAR=False
1316
)
1417

1518
ament_add_test(test_bt_navigator_with_dijkstra
@@ -37,7 +40,7 @@ ament_add_test(test_dynamic_obstacle
3740
TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo_obstacle.world
3841
GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
3942
BT_NAVIGATOR_XML=navigate_w_replanning_and_recovery.xml
40-
ASTAR=True
43+
ASTAR=False
4144
)
4245

4346
# ament_add_test(test_multi_robot

nav2_system_tests/src/system/test_system_launch.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,8 @@ def generate_launch_description():
4141
params_file = os.path.join(bringup_dir, 'params', 'nav2_params.yaml')
4242

4343
# Replace the `use_astar` setting on the params file
44-
param_substitutions = {'GridBased.use_astar': os.getenv('ASTAR')}
44+
param_substitutions = {
45+
'planner_server.ros__parameters.GridBased.use_astar': os.getenv('ASTAR')}
4546
configured_params = RewrittenYaml(
4647
source_file=params_file,
4748
root_key='',

nav2_system_tests/src/system/tester_node.py

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -228,12 +228,8 @@ def run_all_tests(robot_tester):
228228
robot_tester.wait_for_node_active('bt_navigator')
229229
result = robot_tester.runNavigateAction()
230230

231-
# TODO(orduno) Test sending the navigation request through the topic interface.
232-
# Need to update tester to receive multiple goal poses.
233-
# Need to fix bug with shutting down while bt_navigator
234-
# is still running.
235-
# if (result):
236-
# result = test_RobotMovesToGoal(robot_tester)
231+
if (result):
232+
result = test_RobotMovesToGoal(robot_tester)
237233

238234
# Add more tests here if desired
239235

nav2_system_tests/src/waypoint_follower/tester.py

Lines changed: 28 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ def __init__(self):
3737
self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped,
3838
'initialpose', 10)
3939
self.initial_pose_received = False
40+
self.goal_handle = None
4041

4142
pose_qos = QoSProfile(
4243
durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
@@ -71,7 +72,7 @@ def setWaypoints(self, waypoints):
7172
msg.pose.orientation.w = 1.0
7273
self.waypoints.append(msg)
7374

74-
def run(self):
75+
def run(self, block):
7576
if not self.waypoints:
7677
rclpy.error_msg('Did not set valid waypoints before running test!')
7778
return False
@@ -86,16 +87,19 @@ def run(self):
8687
send_goal_future = self.action_client.send_goal_async(action_request)
8788
try:
8889
rclpy.spin_until_future_complete(self, send_goal_future)
89-
goal_handle = send_goal_future.result()
90+
self.goal_handle = send_goal_future.result()
9091
except Exception as e:
9192
self.error_msg('Service call failed %r' % (e,))
9293

93-
if not goal_handle.accepted:
94+
if not self.goal_handle.accepted:
9495
self.error_msg('Goal rejected')
9596
return False
9697

9798
self.info_msg('Goal accepted')
98-
get_result_future = goal_handle.get_result_async()
99+
if not block:
100+
return True
101+
102+
get_result_future = self.goal_handle.get_result_async()
99103

100104
self.info_msg("Waiting for 'FollowWaypoints' action to complete")
101105
try:
@@ -148,14 +152,18 @@ def shutdown(self):
148152
except Exception as e:
149153
self.error_msg('Service call failed %r' % (e,))
150154

155+
def cancel_goal(self):
156+
cancel_future = self.goal_handle.cancel_goal_async()
157+
rclpy.spin_until_future_complete(self, cancel_future)
158+
151159
def info_msg(self, msg: str):
152-
self.get_logger().info('\033[1;37;44m' + msg + '\033[0m')
160+
self.get_logger().info(msg)
153161

154162
def warn_msg(self, msg: str):
155-
self.get_logger().warn('\033[1;37;43m' + msg + '\033[0m')
163+
self.get_logger().warn(msg)
156164

157165
def error_msg(self, msg: str):
158-
self.get_logger().error('\033[1;37;41m' + msg + '\033[0m')
166+
self.get_logger().error(msg)
159167

160168

161169
def main(argv=sys.argv[1:]):
@@ -179,7 +187,19 @@ def main(argv=sys.argv[1:]):
179187
test.info_msg('Waiting for amcl_pose to be received')
180188
rclpy.spin_once(test, timeout_sec=1.0) # wait for poseCallback
181189

182-
result = test.run()
190+
result = test.run(True)
191+
192+
# preempt with new point
193+
test.setWaypoints([starting_pose])
194+
result = test.run(False)
195+
time.sleep(2)
196+
test.setWaypoints([wps[1]])
197+
result = test.run(False)
198+
199+
# cancel
200+
time.sleep(2)
201+
test.cancel_goal()
202+
183203
test.shutdown()
184204
test.info_msg('Done Shutting Down.')
185205

nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,7 @@ class WaypointFollower : public nav2_util::LifecycleNode
115115
std::unique_ptr<ActionServer> action_server_;
116116
ActionClient::SharedPtr nav_to_pose_client_;
117117
rclcpp::Node::SharedPtr client_node_;
118+
std::shared_future<rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr> future_goal_handle_;
118119
bool stop_on_failure_;
119120
ActionStatus current_goal_status_;
120121
int loop_rate_;

nav2_waypoint_follower/src/waypoint_follower.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,8 @@ WaypointFollower::followWaypoints()
132132
while (rclcpp::ok()) {
133133
// Check if asked to stop processing action
134134
if (action_server_->is_cancel_requested()) {
135-
RCLCPP_INFO(get_logger(), "Cancelling action.");
135+
auto cancel_future = nav_to_pose_client_->async_cancel_all_goals();
136+
rclcpp::spin_until_future_complete(client_node_, cancel_future);
136137
action_server_->terminate_all();
137138
return;
138139
}
@@ -156,7 +157,7 @@ WaypointFollower::followWaypoints()
156157
std::bind(&WaypointFollower::resultCallback, this, std::placeholders::_1);
157158
send_goal_options.goal_response_callback =
158159
std::bind(&WaypointFollower::goalResponseCallback, this, std::placeholders::_1);
159-
auto future_goal_handle =
160+
future_goal_handle_ =
160161
nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);
161162
current_goal_status_ = ActionStatus::PROCESSING;
162163
}

0 commit comments

Comments
 (0)