Skip to content

Commit

Permalink
standalone assisted teleop (ros-navigation#2904)
Browse files Browse the repository at this point in the history
* 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 <stevenmacenski@gmail.com>
  • Loading branch information
2 people authored and Joshua Wallace committed Dec 14, 2022
1 parent 344ac1c commit 2b34405
Show file tree
Hide file tree
Showing 30 changed files with 1,622 additions and 2 deletions.
6 changes: 6 additions & 0 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,9 @@ list(APPEND plugin_libs nav2_spin_cancel_bt_node)
add_library(nav2_back_up_cancel_bt_node SHARED plugins/action/back_up_cancel_node.cpp)
list(APPEND plugin_libs nav2_back_up_cancel_bt_node)

add_library(nav2_assisted_teleop_cancel_bt_node SHARED plugins/action/assisted_teleop_cancel_node.cpp)
list(APPEND plugin_libs nav2_assisted_teleop_cancel_bt_node)

add_library(nav2_drive_on_heading_cancel_bt_node SHARED plugins/action/drive_on_heading_cancel_node.cpp)
list(APPEND plugin_libs nav2_drive_on_heading_cancel_bt_node)

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

add_library(nav2_assisted_teleop_action_bt_node SHARED plugins/action/assisted_teleop_action.cpp)
list(APPEND plugin_libs nav2_assisted_teleop_action_bt_node)

add_library(nav2_clear_costmap_service_bt_node SHARED plugins/action/clear_costmap_service.cpp)
list(APPEND plugin_libs nav2_clear_costmap_service_bt_node)

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
// Copyright (c) 2022 Joshua Wallace
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.


#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_ACTION_HPP_
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_ACTION_HPP_

#include <string>

#include "nav2_behavior_tree/bt_action_node.hpp"
#include "nav2_msgs/action/assisted_teleop.hpp"

namespace nav2_behavior_tree
{

/**
* @brief A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::AssistedTeleop
*/
class AssistedTeleopAction : public BtActionNode<nav2_msgs::action::AssistedTeleop>
{
public:
/**
* @brief A constructor for nav2_behavior_tree::nav2_msgs::action::AssistedTeleop
* @param xml_tag_name Name for the XML tag for this node
* @param action_name Action name this node creates a client for
* @param conf BT node configuration
*/
AssistedTeleopAction(
const std::string & xml_tag_name,
const std::string & action_name,
const BT::NodeConfiguration & conf);

/**
* @brief Function to perform some user-defined operation on tick
*/
void on_tick() override;

BT::NodeStatus on_aborted() override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
*/
static BT::PortsList providedPorts()
{
return providedBasicPorts(
{
BT::InputPort<double>("time_allowance", 10.0, "Allowed time for running assisted teleop"),
BT::InputPort<bool>("is_recovery", false, "If true the recovery count will be incremented")
});
}

private:
bool is_recovery_;
};

} // namespace nav2_behavior_tree

#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_ACTION_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
// Copyright (c) 2022 Joshua Wallace
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_CANCEL_NODE_HPP_
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_CANCEL_NODE_HPP_

#include <memory>
#include <string>

#include "nav2_msgs/action/assisted_teleop.hpp"

#include "nav2_behavior_tree/bt_cancel_action_node.hpp"

namespace nav2_behavior_tree
{

/**
* @brief A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::BackUp
*/
class AssistedTeleopCancel : public BtCancelActionNode<nav2_msgs::action::AssistedTeleop>
{
public:
/**
* @brief A constructor for nav2_behavior_tree::BackUpAction
* @param xml_tag_name Name for the XML tag for this node
* @param action_name Action name this node creates a client for
* @param conf BT node configuration
*/
AssistedTeleopCancel(
const std::string & xml_tag_name,
const std::string & action_name,
const BT::NodeConfiguration & conf);

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
*/
static BT::PortsList providedPorts()
{
return providedBasicPorts(
{
});
}
};

} // namespace nav2_behavior_tree

#endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__ASSISTED_TELEOP_CANCEL_NODE_HPP_
12 changes: 12 additions & 0 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,11 @@
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="CancelAssistedTeleop">
<input_port name="service_name">Service name to cancel the assisted teleop behavior</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="CancelWait">
<input_port name="service_name">Service name to cancel the wait behavior</input_port>
<input_port name="server_timeout">Server timeout</input_port>
Expand Down Expand Up @@ -164,6 +169,13 @@
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="AssistedTeleop">
<input_port name="time_allowance">Allowed time for spinning</input_port>
<input_port name="is_recovery">If true recovery count will be incremented</input_port>
<input_port name="server_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<!-- ############################### CONDITION NODES ############################## -->
<Condition ID="GoalReached">
<input_port name="goal">Destination</input_port>
Expand Down
62 changes: 62 additions & 0 deletions nav2_behavior_tree/plugins/action/assisted_teleop_action.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
// Copyright (c) 2022 Joshua Wallace
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <string>
#include <memory>

#include "nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp"

namespace nav2_behavior_tree
{

AssistedTeleopAction::AssistedTeleopAction(
const std::string & xml_tag_name,
const std::string & action_name,
const BT::NodeConfiguration & conf)
: BtActionNode<nav2_msgs::action::AssistedTeleop>(xml_tag_name, action_name, conf)
{
double time_allowance;
getInput("time_allowance", time_allowance);
getInput("is_recovery", is_recovery_);

// Populate the input message
goal_.time_allowance = rclcpp::Duration::from_seconds(time_allowance);
}

void AssistedTeleopAction::on_tick()
{
if (is_recovery_) {
increment_recovery_count();
}
}

BT::NodeStatus AssistedTeleopAction::on_aborted()
{
return is_recovery_ ? BT::NodeStatus::FAILURE : BT::NodeStatus::SUCCESS;
}

} // namespace nav2_behavior_tree

#include "behaviortree_cpp_v3/bt_factory.h"
BT_REGISTER_NODES(factory)
{
BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
{
return std::make_unique<nav2_behavior_tree::AssistedTeleopAction>(
name, "assisted_teleop", config);
};

factory.registerBuilder<nav2_behavior_tree::AssistedTeleopAction>("AssistedTeleop", builder);
}
47 changes: 47 additions & 0 deletions nav2_behavior_tree/plugins/action/assisted_teleop_cancel_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// Copyright (c) 2022 Joshua Wallace
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <string>
#include <memory>

#include "std_msgs/msg/string.hpp"

#include "nav2_behavior_tree/plugins/action/assisted_teleop_cancel_node.hpp"

namespace nav2_behavior_tree
{

AssistedTeleopCancel::AssistedTeleopCancel(
const std::string & xml_tag_name,
const std::string & action_name,
const BT::NodeConfiguration & conf)
: BtCancelActionNode<nav2_msgs::action::AssistedTeleop>(xml_tag_name, action_name, conf)
{
}

} // namespace nav2_behavior_tree

#include "behaviortree_cpp_v3/bt_factory.h"
BT_REGISTER_NODES(factory)
{
BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
{
return std::make_unique<nav2_behavior_tree::AssistedTeleopCancel>(
name, "assisted_teleop", config);
};

factory.registerBuilder<nav2_behavior_tree::AssistedTeleopCancel>(
"CancelAssistedTeleop", builder);
}
8 changes: 8 additions & 0 deletions nav2_behavior_tree/test/plugins/action/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,10 @@ ament_add_gtest(test_action_wait_action test_wait_action.cpp)
target_link_libraries(test_action_wait_action nav2_wait_action_bt_node)
ament_target_dependencies(test_action_wait_action ${dependencies})

ament_add_gtest(test_action_assisted_teleop_action test_assisted_teleop_action.cpp)
target_link_libraries(test_action_assisted_teleop_action nav2_assisted_teleop_action_bt_node)
ament_target_dependencies(test_action_assisted_teleop_action ${dependencies})

ament_add_gtest(test_action_controller_cancel_action test_controller_cancel_node.cpp)
target_link_libraries(test_action_controller_cancel_action nav2_controller_cancel_bt_node)
ament_target_dependencies(test_action_controller_cancel_action ${dependencies})
Expand All @@ -36,6 +40,10 @@ ament_add_gtest(test_action_back_up_cancel_action test_back_up_cancel_node.cpp)
target_link_libraries(test_action_back_up_cancel_action nav2_back_up_cancel_bt_node)
ament_target_dependencies(test_action_back_up_cancel_action ${dependencies})

ament_add_gtest(test_action_assisted_teleop_cancel_action test_assisted_teleop_cancel_node.cpp)
target_link_libraries(test_action_assisted_teleop_cancel_action nav2_assisted_teleop_cancel_bt_node)
ament_target_dependencies(test_action_assisted_teleop_cancel_action ${dependencies})

ament_add_gtest(test_action_drive_on_heading_cancel_action test_drive_on_heading_cancel_node.cpp)
target_link_libraries(test_action_drive_on_heading_cancel_action nav2_drive_on_heading_cancel_bt_node)
ament_target_dependencies(test_action_drive_on_heading_cancel_action ${dependencies})
Expand Down
Loading

0 comments on commit 2b34405

Please sign in to comment.