Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Change to btcpp_v4 #24

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
cmake_minimum_required(VERSION 3.5.1) # version on Ubuntu Trusty
project(behaviortree_ros)

set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_POSITION_INDEPENDENT_CODE ON)

######################################################

set(ROS_DEPENDENCIES
roscpp std_msgs
behaviortree_cpp_v3
behaviortree_cpp
actionlib_msgs
actionlib
message_generation)
Expand Down
7 changes: 3 additions & 4 deletions include/behaviortree_ros/bt_action_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@
#ifndef BEHAVIOR_TREE_BT_ACTION_NODE_HPP_
#define BEHAVIOR_TREE_BT_ACTION_NODE_HPP_

#include <behaviortree_cpp_v3/action_node.h>
#include <behaviortree_cpp_v3/bt_factory.h>
#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <behaviortree_cpp/action_node.h>
#include <behaviortree_cpp/bt_factory.h>
#include <ros/ros.h>

namespace BT
{
Expand Down Expand Up @@ -100,7 +100,6 @@ class RosActionNode : public BT::ActionNodeBase
{
action_client_->cancelGoal();
}
setStatus(NodeStatus::IDLE);
}

protected:
Expand Down
4 changes: 2 additions & 2 deletions include/behaviortree_ros/bt_service_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#ifndef BEHAVIOR_TREE_BT_SERVICE_NODE_HPP_
#define BEHAVIOR_TREE_BT_SERVICE_NODE_HPP_

#include <behaviortree_cpp_v3/action_node.h>
#include <behaviortree_cpp_v3/bt_factory.h>
#include <behaviortree_cpp/action_node.h>
#include <behaviortree_cpp/bt_factory.h>
#include <ros/ros.h>
#include <ros/service_client.h>

Expand Down
22 changes: 8 additions & 14 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<package>
<package format="2">
<name>behaviortree_ros</name>
<version>0.0.1</version>
<description>
Expand All @@ -11,20 +11,14 @@

<author>Davide Faconti</author>

<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>behaviortree_cpp_v3</build_depend>
<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<depend>roscpp</depend>
<depend>std_msgs</depend>
<depend>behaviortree_cpp</depend>
<depend>actionlib</depend>
<depend>actionlib_msgs</depend>

<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>behaviortree_cpp_v3</run_depend>
<run_depend>actionlib</run_depend>
<run_depend>actionlib_msgs</run_depend>

<build_depend>message_generation</build_depend>
<run_depend>message_generation</run_depend>
<exec_depend>message_runtime</exec_depend>
<depend>message_generation</depend>

<buildtool_depend>catkin</buildtool_depend>

Expand Down
8 changes: 4 additions & 4 deletions test/test_bt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,9 +157,9 @@ RosActionNode<behaviortree_ros::FibonacciAction>(handle, name, conf) {}
//-----------------------------------------------------

// Simple tree, used to execute once each action.
static const char* xml_text = R"(
<root >
<BehaviorTree>
static const char* xml_text = R"(
<root BTCPP_format="4" >
<BehaviorTree ID="MainTree">
<Sequence>
<AddTwoInts service_name = "add_two_ints"
first_int = "3" second_int = "4"
Expand Down Expand Up @@ -196,7 +196,7 @@ int main(int argc, char **argv)
while( ros::ok() && (status == NodeStatus::IDLE || status == NodeStatus::RUNNING))
{
ros::spinOnce();
status = tree.tickRoot();
status = tree.tickExactlyOnce();

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What is the main difference between v3 and v4 in this topic?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In bt.v4, tickExactlyOnce calls tickRoot(EXACTLY_ONCE, std::chrono::milliseconds(0));
which will behave the same way tickRoot in bt.v3

In bt.cpp 4 you have other options to tick (e.g. TickOption::WHILE_RUNNING); usage tree.tickRootWhileRunning()

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for answer. Is good to know, but there are some questions related.

About tickOnce method, that implements tickRoot(ONCE_UNLESS_WOKEN_UP, 0s)?
What happens if there is a BT node that emit a wake signal? will it needs to wait for the loop rate?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yes, that is why you have another inner loop:

  while(status == NodeStatus::IDLE ||
        (opt == TickOption::WHILE_RUNNING && status == NodeStatus::RUNNING))
  {
    status = rootNode()->executeTick();

    // Inner loop. The previous tick might have triggered the wake-up
    // in this case, unless TickOption::EXACTLY_ONCE, we tick again
    while(opt != TickOption::EXACTLY_ONCE && status == NodeStatus::RUNNING &&
          wake_up_->waitFor(std::chrono::milliseconds(0)))
    {
      status = rootNode()->executeTick();
    }

if you use tickExactlyOnce it will wait the loop rate to tick again;
tickOnce will tick again if you have a wake_up signal.

StatefulActionNode and Threaded ones may emit a wake_up signal.
You can check the SleepNode for example

std::cout << status << std::endl;
ros::Duration sleep_time(0.01);
sleep_time.sleep();
Expand Down