Skip to content
Merged
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
6 changes: 3 additions & 3 deletions .github/workflows/rolling.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,11 @@ jobs:
run: sudo apt-get install libfl-dev
- uses: actions/checkout@v2
- name: Setup ROS 2
uses: ros-tooling/[email protected].9
uses: ros-tooling/[email protected].13
with:
required-ros-distributions: rolling
- name: build and test
uses: ros-tooling/action-ros-ci@0.3.15
uses: ros-tooling/action-ros-ci@0.4.3
with:
package-name: br2_basics br2_bt_bumpgo br2_bt_patrolling br2_fsm_bumpgo_cpp br2_fsm_bumpgo_py br2_navigation br2_tf2_detector br2_tiago br2_tracking br2_tracking_msgs br2_vff_avoidance
target-ros2-distro: rolling
Expand All @@ -35,4 +35,4 @@ jobs:
"test": {
"parallel-workers" : 1
}
}
}
21 changes: 11 additions & 10 deletions br2_basics/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,35 +1,37 @@
cmake_minimum_required(VERSION 3.5)
project(br2_basics)

set(CMAKE_CXX_STANDARD 23)

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

set(dependencies
rclcpp
std_msgs
rclcpp::rclcpp
${std_msgs_TARGETS}
)

add_executable(publisher src/publisher.cpp)
ament_target_dependencies(publisher ${dependencies})
target_link_libraries(publisher ${dependencies})

add_executable(publisher_class src/publisher_class.cpp)
ament_target_dependencies(publisher_class ${dependencies})
target_link_libraries(publisher_class ${dependencies})

add_executable(subscriber_class src/subscriber_class.cpp)
ament_target_dependencies(subscriber_class ${dependencies})
target_link_libraries(subscriber_class ${dependencies})

add_executable(executors src/executors.cpp)
ament_target_dependencies(executors ${dependencies})
target_link_libraries(executors ${dependencies})

add_executable(logger src/logger.cpp)
ament_target_dependencies(logger ${dependencies})
target_link_libraries(logger ${dependencies})

add_executable(logger_class src/logger_class.cpp)
ament_target_dependencies(logger_class ${dependencies})
target_link_libraries(logger_class ${dependencies})

add_executable(param_reader src/param_reader.cpp)
ament_target_dependencies(param_reader ${dependencies})
target_link_libraries(param_reader ${dependencies})

install(TARGETS
publisher
Expand All @@ -51,5 +53,4 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()

ament_export_dependencies(${dependencies})
ament_package()
45 changes: 25 additions & 20 deletions br2_bt_bumpgo/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,36 +1,35 @@
cmake_minimum_required(VERSION 3.5)
project(br2_bt_bumpgo)

set(CMAKE_CXX_STANDARD 23)

set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake")
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}")

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(behaviortree_cpp_v3 REQUIRED)
find_package(behaviortree_cpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(ament_index_cpp REQUIRED)

find_package(ZMQ)
if(ZMQ_FOUND)
message(STATUS "ZeroMQ found.")
add_definitions(-DZMQ_FOUND)
else()
message(WARNING "ZeroMQ NOT found. Not including PublisherZMQ.")
endif()

set(CMAKE_CXX_STANDARD 17)

set(dependencies
rclcpp::rclcpp
behaviortree_cpp::behaviortree_cpp
ament_index_cpp::ament_index_cpp
${sensor_msgs_TARGETS}
${geometry_msgs_TARGETS}
)

set(export_dependencies
rclcpp
behaviortree_cpp_v3
behaviortree_cpp
ament_index_cpp
sensor_msgs
geometry_msgs
ament_index_cpp
)

include_directories(include ${ZMQ_INCLUDE_DIRS})

add_library(br2_forward_bt_node SHARED src/br2_bt_bumpgo/Forward.cpp)
add_library(br2_back_bt_node SHARED src/br2_bt_bumpgo/Back.cpp)
add_library(br2_turn_bt_node SHARED src/br2_bt_bumpgo/Turn.cpp)
Expand All @@ -44,24 +43,28 @@ list(APPEND plugin_libs
)

foreach(bt_plugin ${plugin_libs})
ament_target_dependencies(${bt_plugin} ${dependencies})
target_include_directories(${bt_plugin} PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
)
target_link_libraries(${bt_plugin} ${dependencies})
target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT)
endforeach()

add_executable(bt_bumpgo src/bt_bumpgo_main.cpp)
ament_target_dependencies(bt_bumpgo ${dependencies})
target_link_libraries(bt_bumpgo ${ZMQ_LIBRARIES})
target_link_libraries(bt_bumpgo ${dependencies})

install(TARGETS
${plugin_libs}
bt_bumpgo
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY include/
DESTINATION include/
DESTINATION include/${PROJECT_NAME}
)

install(DIRECTORY behavior_tree_xml
Expand All @@ -81,7 +84,9 @@ if(BUILD_TESTING)
add_subdirectory(tests)
endif()

ament_export_include_directories(include)
ament_export_dependencies(${dependencies})
ament_export_include_directories("include/${PROJECT_NAME}")
ament_export_libraries(${bt_plugin})
ament_export_dependencies(${export_dependencies})
ament_export_targets(export_${PROJECT_NAME})

ament_package()
2 changes: 1 addition & 1 deletion br2_bt_bumpgo/behavior_tree_xml/bumpgo.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<root main_tree_to_execute="BehaviorTree">
<root BTCPP_format="4" main_tree_to_execute="BehaviorTree">
<!-- ////////// -->
<BehaviorTree ID="BehaviorTree">
<ReactiveSequence>
Expand Down
4 changes: 2 additions & 2 deletions br2_bt_bumpgo/include/br2_bt_bumpgo/Back.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

#include <string>

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp/bt_factory.h"

#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
Expand Down
4 changes: 2 additions & 2 deletions br2_bt_bumpgo/include/br2_bt_bumpgo/Forward.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

#include <string>

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp/bt_factory.h"

#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
Expand Down
4 changes: 2 additions & 2 deletions br2_bt_bumpgo/include/br2_bt_bumpgo/IsObstacle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

#include <string>

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp/bt_factory.h"

#include "sensor_msgs/msg/laser_scan.hpp"
#include "rclcpp/rclcpp.hpp"
Expand Down
4 changes: 2 additions & 2 deletions br2_bt_bumpgo/include/br2_bt_bumpgo/Turn.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

#include <string>

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp/bt_factory.h"

#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
Expand Down
2 changes: 1 addition & 1 deletion br2_bt_bumpgo/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>behaviortree_cpp_v3</depend>
<depend>behaviortree_cpp</depend>
<depend>sensor_msgs</depend>
<depend>geometry_msgs</depend>
<depend>libzmq3-dev</depend>
Expand Down
6 changes: 3 additions & 3 deletions br2_bt_bumpgo/src/br2_bt_bumpgo/Back.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "br2_bt_bumpgo/Back.hpp"

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp/behavior_tree.h"

#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -32,7 +32,7 @@ Back::Back(
const BT::NodeConfiguration & conf)
: BT::ActionNodeBase(xml_tag_name, conf)
{
config().blackboard->get("node", node_);
[[maybe_unused]] bool success = config().blackboard->get("node", node_);

vel_pub_ = node_->create_publisher<geometry_msgs::msg::Twist>("/output_vel", 100);
}
Expand Down Expand Up @@ -64,7 +64,7 @@ Back::tick()

} // namespace br2_bt_bumpgo

#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<br2_bt_bumpgo::Back>("Back");
Expand Down
6 changes: 3 additions & 3 deletions br2_bt_bumpgo/src/br2_bt_bumpgo/Forward.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "br2_bt_bumpgo/Forward.hpp"

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp/behavior_tree.h"

#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -32,7 +32,7 @@ Forward::Forward(
const BT::NodeConfiguration & conf)
: BT::ActionNodeBase(xml_tag_name, conf)
{
config().blackboard->get("node", node_);
[[maybe_unused]] bool success = config().blackboard->get("node", node_);

vel_pub_ = node_->create_publisher<geometry_msgs::msg::Twist>("/output_vel", 100);
}
Expand All @@ -49,7 +49,7 @@ Forward::tick()

} // namespace br2_bt_bumpgo

#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<br2_bt_bumpgo::Forward>("Forward");
Expand Down
6 changes: 3 additions & 3 deletions br2_bt_bumpgo/src/br2_bt_bumpgo/IsObstacle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "br2_bt_bumpgo/IsObstacle.hpp"

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp/behavior_tree.h"

#include "sensor_msgs/msg/laser_scan.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -33,7 +33,7 @@ IsObstacle::IsObstacle(
const BT::NodeConfiguration & conf)
: BT::ConditionNode(xml_tag_name, conf)
{
config().blackboard->get("node", node_);
[[maybe_unused]] bool success = config().blackboard->get("node", node_);

laser_sub_ = node_->create_subscription<sensor_msgs::msg::LaserScan>(
"/input_scan", 100, std::bind(&IsObstacle::laser_callback, this, _1));
Expand Down Expand Up @@ -66,7 +66,7 @@ IsObstacle::tick()

} // namespace br2_bt_bumpgo

#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<br2_bt_bumpgo::IsObstacle>("IsObstacle");
Expand Down
6 changes: 3 additions & 3 deletions br2_bt_bumpgo/src/br2_bt_bumpgo/Turn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "br2_bt_bumpgo/Turn.hpp"

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp/behavior_tree.h"

#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -32,7 +32,7 @@ Turn::Turn(
const BT::NodeConfiguration & conf)
: BT::ActionNodeBase(xml_tag_name, conf)
{
config().blackboard->get("node", node_);
[[maybe_unused]] bool success = config().blackboard->get("node", node_);

vel_pub_ = node_->create_publisher<geometry_msgs::msg::Twist>("/output_vel", 100);
}
Expand Down Expand Up @@ -64,7 +64,7 @@ Turn::tick()

} // namespace br2_bt_bumpgo

#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<br2_bt_bumpgo::Turn>("Turn");
Expand Down
11 changes: 4 additions & 7 deletions br2_bt_bumpgo/src/bt_bumpgo_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,9 @@
#include <string>
#include <memory>

#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp_v3/utils/shared_library.h"
#include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h"
#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp/bt_factory.h"
#include "behaviortree_cpp/utils/shared_library.h"

#include "ament_index_cpp/get_package_share_directory.hpp"

Expand Down Expand Up @@ -46,13 +45,11 @@ int main(int argc, char * argv[])
blackboard->set("node", node);
BT::Tree tree = factory.createTreeFromFile(xml_file, blackboard);

auto publisher_zmq = std::make_shared<BT::PublisherZMQ>(tree, 10, 1666, 1667);

rclcpp::Rate rate(10);

bool finish = false;
while (!finish && rclcpp::ok()) {
finish = tree.rootNode()->executeTick() != BT::NodeStatus::RUNNING;
finish = tree.tickOnce() != BT::NodeStatus::RUNNING;

rclcpp::spin_some(node);
rate.sleep();
Expand Down
5 changes: 2 additions & 3 deletions br2_bt_bumpgo/tests/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@

ament_add_gtest(bt_action_test bt_action_test.cpp)
ament_target_dependencies(bt_action_test ${dependencies})
target_link_libraries(bt_action_test ${dependencies})

add_executable(bt_forward bt_forward_main.cpp)
ament_target_dependencies(bt_forward ${dependencies})
target_link_libraries(bt_forward ${ZMQ_LIBRARIES})
target_link_libraries(bt_forward ${dependencies})

install(TARGETS
bt_forward
Expand Down
Loading