Skip to content

Commit 0d86469

Browse files
SteveMacenskijwallace42AlexeyMerzlyakovenesbedir1Tobias-Fischer
authored
Humble sync 2: Nov 8 (#3274)
* standalone assisted teleop (#2904) * standalone assisted teleop * added in action message * code review * moved to behavior server * added assisted teleop bt node * revert * added bt node for assisted teleop * lint fix * added cancel assisted teleop node * code review * working * cleanup * updated feeback * code review * update compute velocity * cleanup * lint fixes * cleanup * test fix * starting to add tests for assisted teleop * fixed tests * undo * fixed test * is_recovery * adjust abort result based on recovery or not * code review * added preempt velocity * working preempt assisted teleop test * completed assisted teleop tests * code review * undo * code review * remove sleep * topic rename * missing comma * added comma :( * added comma Co-authored-by: Steve Macenski <[email protected]> * Add the support of range sensors to Collision Monitor (#3099) * Support range sensors in Collision Monitor * Adjust README.md * Meet review fixes * Fix #3152: Costmap extend did not include Y component (#3153) * missing nodes added to nav2_tree_nodes.xml (#3155) * Change deprecated ceres function (#3158) * Change deprecated function * Update smoother_cost_function.hpp * remove camera_rgb_joint since child frame does not exist (#3162) * bugfix (#3109) deadlock when costmap receives new map (#3145) * bugfix (#3109) deadlock when costmap receives new map Signed-off-by: Daisuke Sato <[email protected]> * introduce map_received_in_update_bounds_ flag to make sure processMap will not be called between updateBounds and updateCosts Signed-off-by: Daisuke Sato <[email protected]> Signed-off-by: Daisuke Sato <[email protected]> * simple command costmap api - first few functions (#3159) * initial commit costmap_2d template Signed-off-by: Stevedan Omodolor <[email protected]> * finish task A and tested * lint * Update nav2_simple_commander/nav2_simple_commander/costmap_2d.py Co-authored-by: Steve Macenski <[email protected]> * fix trailing underscores Signed-off-by: Stevedan Omodolor <[email protected]> Co-authored-by: Steve Macenski <[email protected]> * Fix missing dependency on nav2_collision_monitor (#3175) * fixed start (#3168) * fixed start * return true * fix tests * Fix velocities comparison for rotation at place case (#3177) * Fix velocities comparison for rotation at place case * Meet review item * Remove unnecessary header * Change the comment * set a empty path on halt (#3178) * set a empty path on halt * fixed issues * remove path reset * fixing * reverting * revert * revert * fixed lint * test fix * uncrusify fix * simple command costmap api - update few functions (#3169) * * add aditional function to costmap_2d.py Signed-off-by: Stevedan Omodolor <[email protected]> Updated-by: Jaehun Kim <[email protected]> * finish task B * Update nav2_simple_commander/nav2_simple_commander/costmap_2d.py * Update method docs * Remove underscores at parameters and split getCost into getCostXY and getCostIdx * Update method docstrings * lint code & update docstring, remove default value of getCostXY * lint code with pep257 & flake8 * clear names for bt nodes (#3183) * [Smac] check if a node exists before creating (#3195) * check if a node exists before creating * invert logic to group like with like * Update a_star.cpp * fixing benchmarkign for planners (#3202) * [Smac] Robin hood data structure improves performance by 10-15%! (#3201) * adding robin_hood unordered_map * using robin_hood node map * ignore robin_hood file * linting * linting cont. for triple pointers * linting cont. for uncrustify * [RPP] Add parameter to enable/disable collision detection (#3204) * [RPP] Add parameter to enable/disable collision detection * [RPP] Update README * Update waffle.model * add benchmark launch file + instructions (#3218) * removing hypotf from smac planner heuristic computation (#3217) * removing hypotf * swapping to node2d sqrt * complete smac planner tolerances (#3219) * Disable Output Buffering (#3220) To ensure await asyncio prints [Processing: %s]' every 30s as expected * fix majority of python linting errors introduced in python costmap API additions to get CI turning over again (#3223) * fix majority of python linting errors * finish linting * Assisted teleop simple commander (#3198) * add assisted teleop to python api * cleanup * assisted teleop demo * rename * lint * code review * trigger build * flake8 fix * break cashe * moved all v11 to v12 * lint fix * remove package dep * change default time allowance * Costmap Filter enabling service (#3229) * Add enabling service to costmap filters * Add service testcase * Fix comment * Use toggle_filter service name * Add binary flip costmap filter (#3228) * Add binary flip costmap filter * Move transformPose, worldToMask, getMaskData to CostmapFilter * Added default parametrized binary filter state * Switched to std_msgs/msg/Bool.msg * Use arbitrary filter values * Update waffle.model * Update waffle.model * Update test_actions.cpp * odom alpha restriction to avoid overflow caused by user-misconfiguration (#3238) * odom alpha restriction * odom alpha code style * odom alpha code style * odom alpha code style * Update controller server goal checker (#3240) * [FIX] Update controller server goal checker * [FIX] Autoformat code * [FIX] Misplaced tabs. Co-authored-by: Pedro Alejandro González <[email protected]> * map-size restriction to avoid overflow and nullptr caused by user-misconfiguration (#3242) * odom alpha restriction * odom alpha code style * odom alpha code style * odom alpha code style * map-size restriction * map-size code style * map-size rejection * map-size codestyle * map-size return false * Add Path Smoothers Benchmarking suite (#3236) * Add Path Smoothers Benchmarking suite * Meet review items * Update tools/smoother_benchmarking/README.md Co-authored-by: Steve Macenski <[email protected]> * Move optional performance patch to the end of README * Fix README Co-authored-by: Steve Macenski <[email protected]> * Fix typo (#3262) * Adding new Nav2 Smoother: Savitzky-Golay Smoother (#3264) * initial prototype of the Savitzky Golay Filter Path Smoother * fixed indexing issue - tested working * updates for filter * adding unit tests for SG-filter smoother * adding lifecycle transitions * Added Line Iterator (#3197) * Added Line Iterator * Updated Line Iterator to a new iteration method * Added the resolution as a parameter/ fixed linting * Added the resolution as a parameter/ fixed linting * Added unittests for the line iterator * Added unittests based on "unittest" package * Fixed __init__.py and rephrased some docstrings * Fixed linting errors * Fixed Linting Errors * Added some unittests and removed some methods * Dummy commit for CircleCI Issue Co-authored-by: Afif Swaidan <[email protected]> * bumping to 1.1.3 for release Signed-off-by: Daisuke Sato <[email protected]> Signed-off-by: Stevedan Omodolor <[email protected]> Co-authored-by: Joshua Wallace <[email protected]> Co-authored-by: Alexey Merzlyakov <[email protected]> Co-authored-by: Abdullah Enes BEDİR <[email protected]> Co-authored-by: Tobias Fischer <[email protected]> Co-authored-by: Tejas Kumar Shastha <[email protected]> Co-authored-by: Daisuke Sato <[email protected]> Co-authored-by: Stevedan Ogochukwu Omodolor <[email protected]> Co-authored-by: Lukas Fanta <[email protected]> Co-authored-by: Jackson9 <[email protected]> Co-authored-by: Ruffin <[email protected]> Co-authored-by: Hao-Xuan Song <[email protected]> Co-authored-by: Nicolas Rocha Pacheco <[email protected]> Co-authored-by: Pedro Alejandro González <[email protected]> Co-authored-by: jaeminSHIN <[email protected]> Co-authored-by: Afif Swaidan <[email protected]> Co-authored-by: Afif Swaidan <[email protected]>
1 parent 48c7dc0 commit 0d86469

File tree

179 files changed

+8989
-484
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

179 files changed

+8989
-484
lines changed

.circleci/config.yml

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,12 @@ _commands:
3333
- restore_cache:
3434
name: Restore Cache << parameters.key >>
3535
keys:
36-
- "<< parameters.key >>-v11\
36+
- "<< parameters.key >>-v12\
3737
-{{ arch }}\
3838
-{{ .Branch }}\
3939
-{{ .Environment.CIRCLE_PR_NUMBER }}\
4040
-{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}"
41-
- "<< parameters.key >>-v11\
41+
- "<< parameters.key >>-v12\
4242
-{{ arch }}\
4343
-main\
4444
-<no value>\
@@ -58,7 +58,7 @@ _commands:
5858
steps:
5959
- save_cache:
6060
name: Save Cache << parameters.key >>
61-
key: "<< parameters.key >>-v11\
61+
key: "<< parameters.key >>-v12\
6262
-{{ arch }}\
6363
-{{ .Branch }}\
6464
-{{ .Environment.CIRCLE_PR_NUMBER }}\
@@ -447,6 +447,7 @@ _environments:
447447
RCUTILS_LOGGING_BUFFERED_STREAM: "0"
448448
RCUTILS_LOGGING_USE_STDOUT: "0"
449449
DEBIAN_FRONTEND: "noninteractive"
450+
PYTHONUNBUFFERED: "1"
450451

451452
executors:
452453
release_exec:

Dockerfile

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@ RUN echo '\
4343
APT::Install-Recommends "0";\n\
4444
APT::Install-Suggests "0";\n\
4545
' > /etc/apt/apt.conf.d/01norecommend
46+
ENV PYTHONUNBUFFERED 1
4647

4748
# install CI dependencies
4849
ARG RTI_NC_LICENSE_ACCEPTED=yes

nav2_amcl/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_amcl</name>
5-
<version>1.1.2</version>
5+
<version>1.1.3</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_amcl/src/amcl_node.cpp

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1158,18 +1158,53 @@ AmclNode::dynamicParametersCallback(
11581158
if (param_type == ParameterType::PARAMETER_DOUBLE) {
11591159
if (param_name == "alpha1") {
11601160
alpha1_ = parameter.as_double();
1161+
//alpha restricted to be non-negative
1162+
if (alpha1_ < 0.0) {
1163+
RCLCPP_WARN(
1164+
get_logger(), "You've set alpha1 to be negative,"
1165+
" this isn't allowed, so the alpha1 will be set to be zero.");
1166+
alpha1_ = 0.0;
1167+
}
11611168
reinit_odom = true;
11621169
} else if (param_name == "alpha2") {
11631170
alpha2_ = parameter.as_double();
1171+
//alpha restricted to be non-negative
1172+
if (alpha2_ < 0.0) {
1173+
RCLCPP_WARN(
1174+
get_logger(), "You've set alpha2 to be negative,"
1175+
" this isn't allowed, so the alpha2 will be set to be zero.");
1176+
alpha2_ = 0.0;
1177+
}
11641178
reinit_odom = true;
11651179
} else if (param_name == "alpha3") {
11661180
alpha3_ = parameter.as_double();
1181+
//alpha restricted to be non-negative
1182+
if (alpha3_ < 0.0) {
1183+
RCLCPP_WARN(
1184+
get_logger(), "You've set alpha3 to be negative,"
1185+
" this isn't allowed, so the alpha3 will be set to be zero.");
1186+
alpha3_ = 0.0;
1187+
}
11671188
reinit_odom = true;
11681189
} else if (param_name == "alpha4") {
11691190
alpha4_ = parameter.as_double();
1191+
//alpha restricted to be non-negative
1192+
if (alpha4_ < 0.0) {
1193+
RCLCPP_WARN(
1194+
get_logger(), "You've set alpha4 to be negative,"
1195+
" this isn't allowed, so the alpha4 will be set to be zero.");
1196+
alpha4_ = 0.0;
1197+
}
11701198
reinit_odom = true;
11711199
} else if (param_name == "alpha5") {
11721200
alpha5_ = parameter.as_double();
1201+
//alpha restricted to be non-negative
1202+
if (alpha5_ < 0.0) {
1203+
RCLCPP_WARN(
1204+
get_logger(), "You've set alpha5 to be negative,"
1205+
" this isn't allowed, so the alpha5 will be set to be zero.");
1206+
alpha5_ = 0.0;
1207+
}
11731208
reinit_odom = true;
11741209
} else if (param_name == "beam_skip_distance") {
11751210
beam_skip_distance_ = parameter.as_double();

nav2_behavior_tree/CMakeLists.txt

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,9 @@ list(APPEND plugin_libs nav2_spin_cancel_bt_node)
6969
add_library(nav2_back_up_cancel_bt_node SHARED plugins/action/back_up_cancel_node.cpp)
7070
list(APPEND plugin_libs nav2_back_up_cancel_bt_node)
7171

72+
add_library(nav2_assisted_teleop_cancel_bt_node SHARED plugins/action/assisted_teleop_cancel_node.cpp)
73+
list(APPEND plugin_libs nav2_assisted_teleop_cancel_bt_node)
74+
7275
add_library(nav2_drive_on_heading_cancel_bt_node SHARED plugins/action/drive_on_heading_cancel_node.cpp)
7376
list(APPEND plugin_libs nav2_drive_on_heading_cancel_bt_node)
7477

@@ -90,6 +93,9 @@ list(APPEND plugin_libs nav2_spin_action_bt_node)
9093
add_library(nav2_wait_action_bt_node SHARED plugins/action/wait_action.cpp)
9194
list(APPEND plugin_libs nav2_wait_action_bt_node)
9295

96+
add_library(nav2_assisted_teleop_action_bt_node SHARED plugins/action/assisted_teleop_action.cpp)
97+
list(APPEND plugin_libs nav2_assisted_teleop_action_bt_node)
98+
9399
add_library(nav2_clear_costmap_service_bt_node SHARED plugins/action/clear_costmap_service.cpp)
94100
list(APPEND plugin_libs nav2_clear_costmap_service_bt_node)
95101

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,70 @@
1+
// Copyright (c) 2022 Joshua Wallace
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
16+
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_ACTION_HPP_
17+
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_ACTION_HPP_
18+
19+
#include <string>
20+
21+
#include "nav2_behavior_tree/bt_action_node.hpp"
22+
#include "nav2_msgs/action/assisted_teleop.hpp"
23+
24+
namespace nav2_behavior_tree
25+
{
26+
27+
/**
28+
* @brief A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::AssistedTeleop
29+
*/
30+
class AssistedTeleopAction : public BtActionNode<nav2_msgs::action::AssistedTeleop>
31+
{
32+
public:
33+
/**
34+
* @brief A constructor for nav2_behavior_tree::nav2_msgs::action::AssistedTeleop
35+
* @param xml_tag_name Name for the XML tag for this node
36+
* @param action_name Action name this node creates a client for
37+
* @param conf BT node configuration
38+
*/
39+
AssistedTeleopAction(
40+
const std::string & xml_tag_name,
41+
const std::string & action_name,
42+
const BT::NodeConfiguration & conf);
43+
44+
/**
45+
* @brief Function to perform some user-defined operation on tick
46+
*/
47+
void on_tick() override;
48+
49+
BT::NodeStatus on_aborted() override;
50+
51+
/**
52+
* @brief Creates list of BT ports
53+
* @return BT::PortsList Containing basic ports along with node-specific ports
54+
*/
55+
static BT::PortsList providedPorts()
56+
{
57+
return providedBasicPorts(
58+
{
59+
BT::InputPort<double>("time_allowance", 10.0, "Allowed time for running assisted teleop"),
60+
BT::InputPort<bool>("is_recovery", false, "If true the recovery count will be incremented")
61+
});
62+
}
63+
64+
private:
65+
bool is_recovery_;
66+
};
67+
68+
} // namespace nav2_behavior_tree
69+
70+
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_ACTION_HPP_
Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
// Copyright (c) 2022 Joshua Wallace
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_CANCEL_NODE_HPP_
16+
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_CANCEL_NODE_HPP_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include "nav2_msgs/action/assisted_teleop.hpp"
22+
23+
#include "nav2_behavior_tree/bt_cancel_action_node.hpp"
24+
25+
namespace nav2_behavior_tree
26+
{
27+
28+
/**
29+
* @brief A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::BackUp
30+
*/
31+
class AssistedTeleopCancel : public BtCancelActionNode<nav2_msgs::action::AssistedTeleop>
32+
{
33+
public:
34+
/**
35+
* @brief A constructor for nav2_behavior_tree::BackUpAction
36+
* @param xml_tag_name Name for the XML tag for this node
37+
* @param action_name Action name this node creates a client for
38+
* @param conf BT node configuration
39+
*/
40+
AssistedTeleopCancel(
41+
const std::string & xml_tag_name,
42+
const std::string & action_name,
43+
const BT::NodeConfiguration & conf);
44+
45+
/**
46+
* @brief Creates list of BT ports
47+
* @return BT::PortsList Containing basic ports along with node-specific ports
48+
*/
49+
static BT::PortsList providedPorts()
50+
{
51+
return providedBasicPorts(
52+
{
53+
});
54+
}
55+
};
56+
57+
} // namespace nav2_behavior_tree
58+
59+
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_CANCEL_NODE_HPP_

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,11 @@ class ComputePathToPoseAction : public BtActionNode<nav2_msgs::action::ComputePa
6161
*/
6262
BT::NodeStatus on_cancelled() override;
6363

64+
/**
65+
* \brief Override required by the a BT action. Cancel the action and set the path output
66+
*/
67+
void halt() override;
68+
6469
/**
6570
* @brief Creates list of BT ports
6671
* @return BT::PortsList Containing basic ports along with node-specific ports

nav2_behavior_tree/nav2_tree_nodes.xml

Lines changed: 25 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@
3333
<input_port name="server_timeout">Server timeout</input_port>
3434
</Action>
3535

36-
<Action ID="DriveOnHeadingCancel">
36+
<Action ID="CancelDriveOnHeading">
3737
<input_port name="service_name">Service name to cancel the drive on heading behavior</input_port>
3838
<input_port name="server_timeout">Server timeout</input_port>
3939
</Action>
@@ -43,6 +43,11 @@
4343
<input_port name="server_timeout">Server timeout</input_port>
4444
</Action>
4545

46+
<Action ID="CancelAssistedTeleop">
47+
<input_port name="service_name">Service name to cancel the assisted teleop behavior</input_port>
48+
<input_port name="server_timeout">Server timeout</input_port>
49+
</Action>
50+
4651
<Action ID="CancelWait">
4752
<input_port name="service_name">Service name to cancel the wait behavior</input_port>
4853
<input_port name="server_timeout">Server timeout</input_port>
@@ -53,6 +58,18 @@
5358
<input_port name="server_timeout">Server timeout</input_port>
5459
</Action>
5560

61+
<Action ID="ClearCostmapExceptRegion">
62+
<input_port name="service_name">Service name</input_port>
63+
<input_port name="server_timeout">Server timeout</input_port>
64+
<input_port name="reset_distance">Distance from the robot above which obstacles are cleared</input_port>
65+
</Action>
66+
67+
<Action ID="ClearCostmapAroundRobot">
68+
<input_port name="service_name">Service name</input_port>
69+
<input_port name="server_timeout">Server timeout</input_port>
70+
<input_port name="reset_distance">Distance from the robot under which obstacles are cleared</input_port>
71+
</Action>
72+
5673
<Action ID="ComputePathToPose">
5774
<input_port name="goal">Destination to plan to</input_port>
5875
<input_port name="start">Start pose of the path if overriding current robot pose</input_port>
@@ -164,6 +181,13 @@
164181
<input_port name="server_timeout">Server timeout</input_port>
165182
</Action>
166183

184+
<Action ID="AssistedTeleop">
185+
<input_port name="time_allowance">Allowed time for spinning</input_port>
186+
<input_port name="is_recovery">If true recovery count will be incremented</input_port>
187+
<input_port name="server_name">Service name</input_port>
188+
<input_port name="server_timeout">Server timeout</input_port>
189+
</Action>
190+
167191
<!-- ############################### CONDITION NODES ############################## -->
168192
<Condition ID="GoalReached">
169193
<input_port name="goal">Destination</input_port>

nav2_behavior_tree/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_behavior_tree</name>
5-
<version>1.1.2</version>
5+
<version>1.1.3</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Carlos Orduno</maintainer>

0 commit comments

Comments
 (0)