diff --git a/.github/workflows/pull-request-audit.yaml b/.github/workflows/pull-request-audit.yaml index f9dc01f..96dc23c 100644 --- a/.github/workflows/pull-request-audit.yaml +++ b/.github/workflows/pull-request-audit.yaml @@ -2,26 +2,26 @@ name: pull-request-audit on: push: - branches: [main] + branches: [ros2] pull_request: - branches: [main] + branches: [ros2] workflow_dispatch: - branches: [main] + branches: [ros2] jobs: build: - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 steps: - uses: actions/checkout@v2 with: - path: catkin_ws/src/hbba_lite + path: colcon_ws/src/hbba_lite - uses: ros-tooling/setup-ros@v0.7 with: - required-ros-distributions: noetic + required-ros-distributions: humble - name: Install system dependencies run: | @@ -29,13 +29,14 @@ jobs: sudo apt-get install libgecode-dev - name: Compile packages in ROS workspace - working-directory: catkin_ws + working-directory: colcon_ws run: | - source /opt/ros/noetic/setup.bash - catkin_make -j1 + source /opt/ros/humble/setup.bash + colcon build - name: Run tests - working-directory: catkin_ws + working-directory: colcon_ws run: | - source /opt/ros/noetic/setup.bash - catkin_make run_tests + source /opt/ros/humble/setup.bash + colcon test --packages-up-to hbba_lite + colcon test-result --all --verbose diff --git a/CMakeLists.txt b/CMakeLists.txt deleted file mode 100644 index d55ddeb..0000000 --- a/CMakeLists.txt +++ /dev/null @@ -1,288 +0,0 @@ -cmake_minimum_required(VERSION 3.0.2) -project(hbba_lite) - -## Compile as C++11, supported in ROS Kinetic and newer -set(CMAKE_CXX_STANDARD 17) -set(CMAKE_CXX_STANDARD_REQUIRED ON) - -## Find catkin macros and libraries -## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) -## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS - message_generation - roscpp - rospy - message_filters - std_msgs - topic_tools - ) - -## System dependencies are found with CMake's conventions -# find_package(Boost REQUIRED COMPONENTS system) - - -## Uncomment this if the package has a setup.py. This macro ensures -## modules and global scripts declared therein get installed -## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html -catkin_python_setup() - -################################################ -## Declare ROS messages, services and actions ## -################################################ - -## To declare and build messages, services or actions from within this -## package, follow these steps: -## * Let MSG_DEP_SET be the set of packages whose message types you use in -## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). -## * In the file package.xml: -## * add a build_depend tag for "message_generation" -## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET -## * If MSG_DEP_SET isn't empty the following dependency has been pulled in -## but can be declared for certainty nonetheless: -## * add a exec_depend tag for "message_runtime" -## * In this file (CMakeLists.txt): -## * add "message_generation" and every package in MSG_DEP_SET to -## find_package(catkin REQUIRED COMPONENTS ...) -## * add "message_runtime" and every package in MSG_DEP_SET to -## catkin_package(CATKIN_DEPENDS ...) -## * uncomment the add_*_files sections below as needed -## and list every .msg/.srv/.action file to be processed -## * uncomment the generate_messages entry below -## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) - -## Generate messages in the 'msg' folder -add_message_files( - FILES - Int32Stamped.msg - StrategyState.msg -) - -## Generate services in the 'srv' folder -add_service_files( - FILES - SetOnOffFilterState.srv - SetThrottlingFilterState.srv -) - -## Generate actions in the 'action' folder -# add_action_files( -# FILES -# Action1.action -# Action2.action -# ) - -## Generate added messages and services with any dependencies listed here -generate_messages( - DEPENDENCIES - std_msgs -) - -################################################ -## Declare ROS dynamic reconfigure parameters ## -################################################ - -## To declare and build dynamic reconfigure parameters within this -## package, follow these steps: -## * In the file package.xml: -## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" -## * In this file (CMakeLists.txt): -## * add "dynamic_reconfigure" to -## find_package(catkin REQUIRED COMPONENTS ...) -## * uncomment the "generate_dynamic_reconfigure_options" section below -## and list every .cfg file to be processed - -## Generate dynamic reconfigure parameters in the 'cfg' folder -# generate_dynamic_reconfigure_options( -# cfg/DynReconf1.cfg -# cfg/DynReconf2.cfg -# ) - -################################### -## catkin specific configuration ## -################################### -## The catkin_package macro generates cmake config files for your package -## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if your package contains header files -## LIBRARIES: libraries you create in this project that dependent projects also need -## CATKIN_DEPENDS: catkin_packages dependent projects also need -## DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( - INCLUDE_DIRS include - LIBRARIES hbba_lite - CATKIN_DEPENDS message_generation message_runtime roscpp rospy - # DEPENDS system_lib -) - -########### -## Build ## -########### - -## Specify additional locations of header files -## Your package locations should be listed before other locations -include_directories( - include - ${catkin_INCLUDE_DIRS} -) - -## Declare a C++ library -add_library(${PROJECT_NAME} - src/hbba_lite_cpp/filters/FilterState.cpp - src/hbba_lite_cpp/utils/HbbaLiteException.cpp - src/hbba_lite_cpp/core/Desire.cpp - src/hbba_lite_cpp/core/DesireSet.cpp - src/hbba_lite_cpp/core/Motivation.cpp - src/hbba_lite_cpp/core/Strategy.cpp - src/hbba_lite_cpp/core/RosFilterPool.cpp - src/hbba_lite_cpp/core/Solver.cpp - src/hbba_lite_cpp/core/GecodeSolver.cpp - src/hbba_lite_cpp/core/StrategyStateLogger.cpp - src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp - src/hbba_lite_cpp/core/HbbaLite.cpp - ) - -## Add cmake target dependencies of the library -## as an example, code may need to be generated before libraries -## either from message generation or dynamic reconfigure -add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Declare a C++ executable -## With catkin_make all packages are built within a single CMake context -## The recommended prefix ensures that target names across packages don't collide -add_executable(arbitration_node src/arbitration_node.cpp) -add_executable(on_off_hbba_filter_node src/on_off_hbba_filter_node.cpp) -add_executable(throttling_hbba_filter_node src/throttling_hbba_filter_node.cpp) - -add_executable(test_on_off_hbba_subscriber src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp) -add_executable(test_throttling_hbba_subscriber src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp) -add_executable(test_on_off_hbba_publisher src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp) -add_executable(test_throttling_hbba_publisher src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp) - -## Rename C++ executable without prefix -## The above recommended prefix causes long target names, the following renames the -## target back to the shorter version for ease of user use -## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" -# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") - -## Add cmake target dependencies of the executable -## same as for the library above -# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Specify libraries to link a library or executable target against -target_link_libraries(${PROJECT_NAME} - ${catkin_LIBRARIES} - gecodeflatzinc - gecodedriver - gecodegist - gecodesearch - gecodeminimodel - gecodeset - gecodefloat - gecodeint - gecodekernel - gecodesupport - ) - -target_link_libraries(arbitration_node - ${catkin_LIBRARIES} - ${PROJECT_NAME} - ) -target_link_libraries(on_off_hbba_filter_node - ${catkin_LIBRARIES} - ${PROJECT_NAME} - ) -target_link_libraries(throttling_hbba_filter_node - ${catkin_LIBRARIES} - ${PROJECT_NAME} - ) - -target_link_libraries(test_on_off_hbba_subscriber - ${catkin_LIBRARIES} - ${PROJECT_NAME} - ) -target_link_libraries(test_throttling_hbba_subscriber - ${catkin_LIBRARIES} - ${PROJECT_NAME} - ) -target_link_libraries(test_on_off_hbba_publisher - ${catkin_LIBRARIES} - ${PROJECT_NAME} - ) -target_link_libraries(test_throttling_hbba_publisher - ${catkin_LIBRARIES} - ${PROJECT_NAME} - ) - -############# -## Install ## -############# - -# all install targets should use catkin DESTINATION variables -# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html - -## Mark executable scripts (Python etc.) for installation -## in contrast to setup.py, you can choose the destination -# catkin_install_python(PROGRAMS -# scripts/my_python_script -# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark executables for installation -## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html -# install(TARGETS ${PROJECT_NAME}_node -# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark libraries for installation -## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html -install(TARGETS ${PROJECT_NAME} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} - ) - -## Mark cpp header files for installation -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.h" - PATTERN ".svn" EXCLUDE - ) - -## Mark other files for installation (e.g. launch and bag files, etc.) -# install(FILES -# # myfile1 -# # myfile2 -# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -# ) - -############# -## Testing ## -############# - -## Add gtest based cpp test target and link libraries -catkin_add_gtest(${PROJECT_NAME}-test - test/hbba_lite_cpp/core/DesireTests.cpp - test/hbba_lite_cpp/core/DesireSetTests.cpp - test/hbba_lite_cpp/core/StrategyTests.cpp - test/hbba_lite_cpp/core/SolverTests.cpp - test/hbba_lite_cpp/core/GecodeSolverTests.cpp - test/hbba_lite_cpp/core/HbbaLiteTests.cpp - test/hbba_lite_cpp/main.cpp - ) -if (TARGET ${PROJECT_NAME}-test) - target_link_libraries(${PROJECT_NAME}-test - ${PROJECT_NAME} - gecodeflatzinc - gecodedriver - gecodegist - gecodesearch - gecodeminimodel - gecodeset - gecodefloat - gecodeint - gecodekernel - gecodesupport - ) -endif () - -## Add folders to be run by python nosetests -# catkin_add_nosetests(test) diff --git a/README.md b/README.md index edaacd2..51fcbba 100644 --- a/README.md +++ b/README.md @@ -2,6 +2,8 @@ This is a lite version of [HBBA](https://github.com/francoisferland/hbba). +For ROS1, please see the `ros1` branch. + The main differences are : - Desires cannot have dependencies; @@ -139,49 +141,53 @@ Also, the strategy removes the desire of the set once the desire is completed. class TalkStrategy : public Strategy { std::shared_ptr m_desireSet; - ros::NodeHandle& m_nodeHandle; - ros::Publisher m_talkPublisher; - ros::Subscriber m_talkDoneSubscriber; + std::shared_ptr m_node; + rclcpp::Publisher::SharedPtr m_talkPublisher; + rclcpp::Subscription::SharedPtr m_talkDoneSubscriber; public: TalkStrategy( - uint16_t utility, // The utility of the strategy - std::shared_ptr filterPool, // The instance of the class to change the filter state. + uint16_t utility, + std::shared_ptr filterPool, std::shared_ptr desireSet, - ros::NodeHandle& nodeHandle) + std::shared_ptr node) : Strategy( - utility, - {{"sound", 1}}, // Declare the resources used by the strategy. - {{"talk/filter_state", FilterConfiguration::onOff()}}, // Declare the filters to enable and their type. - move(filterPool)), - m_desireSet(move(desireSet)), - m_nodeHandle(nodeHandle) + utility, + {{"sound", 1}}, + {{"talk/filter_state", FilterConfiguration::onOff()}}, + move(filterPool)), + m_desireSet(move(desireSet)), + m_node(move(node)) { - // Create the publisher to send the text to say. - m_talkPublisher = nodeHandle.advertise("talk/text", 1, true); - - // Create the subscriber to be notified when the text has been said. - m_talkDoneSubscriber = nodeHandle.subscribe("talk/done", 10, &TalkStrategy::talkDoneSubscriberCallback, this); + m_talkPublisher = node->create_publisher( + "talk/text", + rclcpp::QoS(1).transient_local()); + m_talkDoneSubscriber = node->create_subscription( + "talk/done", + 1, + [this](const behavior_msgs::msg::Done::SharedPtr msg) { talkDoneSubscriberCallback(msg); }); } DECLARE_NOT_COPYABLE(TalkStrategy); DECLARE_NOT_MOVABLE(TalkStrategy); + StrategyType strategyType() override + { + return StrategyType::get(); + } + protected: - // Override the method to publish a message when the strategy is enabled. void onEnabling(const TalkDesire& desire) override { - // Publish the text to be said. - talk::Text msg; + behavior_msgs::msg::Text msg; msg.text = desire.text(); msg.id = desire.id(); - m_talkPublisher.publish(msg); + m_talkPublisher->publish(msg); } private: - void talkDoneSubscriberCallback(const talk::Done::ConstPtr& msg) + void talkDoneSubscriberCallback(const behavior_msgs::msg::Done::SharedPtr msg) { - // Remove the desire once the text is said. if (msg->id == desireId()) { m_desireSet->removeDesire(msg->id); @@ -367,30 +373,30 @@ HbbaLite hbba(desireSet, #### Subscriber ```cpp -#include -#include +#include +#include #include -void callback(const std_msgs::Int8::ConstPtr& msg) +void callback(const std_msgs::msg::Int8::ConstPtr& msg) { ROS_INFO("Data received : %i", static_cast(msg->data)); } int main(int argc, char** argv) { - ros::init(argc, argv, "node_name"); - ros::NodeHandle nodeHandle; + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("node_name"); // Replace this - ros::Subscriber sub = n.subscribe("int_topic", 10, callback); + auto sub = node->create_subscription("int_topic", 10, callback); // with this to add an on/off filter - OnOffHbbaSubscriber sub(nodeHandle, "int_topic", 10, &callback); + OnOffHbbaSubscriber sub(node, "int_topic", 10, &callback); // with this to add a throttling filter - ThrottlingHbbaSubscriber sub(nodeHandle, "int_topic", 10, &callback); - ros::spin(); + ThrottlingHbbaSubscriber sub(node, "int_topic", 10, &callback); + rclcpp::spin(node); return 0; } @@ -406,17 +412,17 @@ int main(int argc, char** argv) int main(int argc, char** argv) { - ros::init(argc, argv, "node_name"); - ros::NodeHandle nodeHandle; + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("node_name"); // Replace this - ros::Publisher pub = n.advertise("int_topic", 10); + auto pub = node->create_publisher("int_topic", 10); // with this to add an on/off filter - OnOffHbbaPublisher pub(nodeHandle, "int_topic", 10); + OnOffHbbaPublisher pub(node, "int_topic", 10); // with this to add a throttling filter - ThrottlingHbbaPublisher pub(nodeHandle, "int_topic", 10); + ThrottlingHbbaPublisher pub(node, "int_topic", 10); return 0; } @@ -491,8 +497,9 @@ This node applies priority arbitration to topics. #### Parameters -- `topics`: The topic descriptions containing the topic name (string), priority (int, lower means higher priority) and timeout_s value (double). -- `latch` (bool): Indicates if the output topic is latched. +- `topics` (string): The topic names. +- `priorities` (int): The priority for each topic (int, lower means higher priority). +- `timeout_s` (double): The timeout in seconds for each topic. #### Published Topics @@ -502,25 +509,37 @@ This node applies priority arbitration to topics. This node applies an on/off filter on a topic. +#### Parameters + +- `input_topic` (string): The input topic name. +- `output_topic` (string): The filtered topic name. +- `state_service` (string): The service name to change the filter state. + #### Topics -- `in` (Any): The input topic. -- `out` (Any): The filtered topic. +- Defined by the parameter `input_topic` (Any): The input topic. +- Defined by the parameter `output_topic` (Any): The filtered topic. #### Services -- `filter_state` ([hbba_lite/SetOnOffFilterState](srv/SetOnOffFilterState.srv)) The service to change the filter state. +- Defined by the parameter `state_service` ([hbba_lite_srvs/SetOnOffFilterState](srv/SetOnOffFilterState.srv)): The service to change the filter state. ### `throttling_hbba_filter_node` This node applies a throttling filter on a topic. +#### Parameters + +- `input_topic` (string): The input topic name. +- `output_topic` (string): The filtered topic name. +- `state_service` (string): The service name to change the filter state. + #### Topics -- `in` (Any): The input topic. -- `out` (Any): The filtered topic. +- Defined by the parameter `input_topic` (Any): The input topic. +- Defined by the parameter `output_topic` (Any): The filtered topic. #### Services -- `filter_state` ([hbba_lite/SetThrottlingFilterState](srv/SetThrottlingFilterState.srv)) The service to change the +- Defined by the parameter `state_service` ([hbba_lite_srvs/SetThrottlingFilterState](srv/SetThrottlingFilterState.srv)) The service to change the filter state. diff --git a/hbba_lite/CMakeLists.txt b/hbba_lite/CMakeLists.txt new file mode 100644 index 0000000..7d0f071 --- /dev/null +++ b/hbba_lite/CMakeLists.txt @@ -0,0 +1,153 @@ +cmake_minimum_required(VERSION 3.5) +project(hbba_lite) + + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclpy REQUIRED) +find_package(std_msgs REQUIRED) +find_package(hbba_lite_msgs REQUIRED) +find_package(hbba_lite_srvs REQUIRED) +find_package(message_filters REQUIRED) + +add_library(hbba_lite_cpp + src/hbba_lite_cpp/filters/FilterState.cpp + src/hbba_lite_cpp/utils/HbbaLiteException.cpp + src/hbba_lite_cpp/core/Desire.cpp + src/hbba_lite_cpp/core/DesireSet.cpp + src/hbba_lite_cpp/core/Motivation.cpp + src/hbba_lite_cpp/core/Strategy.cpp + src/hbba_lite_cpp/core/RosFilterPool.cpp + src/hbba_lite_cpp/core/Solver.cpp + src/hbba_lite_cpp/core/GecodeSolver.cpp + src/hbba_lite_cpp/core/StrategyStateLogger.cpp + src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp + src/hbba_lite_cpp/core/HbbaLite.cpp +) +target_include_directories(hbba_lite_cpp + PUBLIC + $ + $ +) +ament_target_dependencies(hbba_lite_cpp rclcpp hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(hbba_lite_cpp + gecodeflatzinc + gecodedriver + gecodegist + gecodesearch + gecodeminimodel + gecodeset + gecodefloat + gecodeint + gecodekernel + gecodesupport +) +ament_export_targets(export_hbba_lite_cpp HAS_LIBRARY_TARGET) +ament_export_dependencies(rclcpp hbba_lite_msgs hbba_lite_srvs) + +install( + TARGETS hbba_lite_cpp + EXPORT export_hbba_lite_cpp + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +install( + DIRECTORY include/ + DESTINATION include +) + +# C++ Nodes +add_executable(arbitration_node src/arbitration_node.cpp) +ament_target_dependencies(arbitration_node rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(arbitration_node hbba_lite_cpp) +install(TARGETS arbitration_node DESTINATION lib/${PROJECT_NAME}) + +add_executable(on_off_hbba_filter_node src/on_off_hbba_filter_node.cpp) +ament_target_dependencies(on_off_hbba_filter_node rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(on_off_hbba_filter_node hbba_lite_cpp) +install(TARGETS on_off_hbba_filter_node DESTINATION lib/${PROJECT_NAME}) + +add_executable(throttling_hbba_filter_node src/throttling_hbba_filter_node.cpp) +ament_target_dependencies(throttling_hbba_filter_node rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(throttling_hbba_filter_node hbba_lite_cpp) +install(TARGETS throttling_hbba_filter_node DESTINATION lib/${PROJECT_NAME}) + +# C++ Test Nodes +add_executable(test_on_off_hbba_publisher src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp) +ament_target_dependencies(test_on_off_hbba_publisher rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(test_on_off_hbba_publisher hbba_lite_cpp) +install(TARGETS test_on_off_hbba_publisher DESTINATION lib/${PROJECT_NAME}) + +add_executable(test_on_off_hbba_subscriber src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp) +ament_target_dependencies(test_on_off_hbba_subscriber rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(test_on_off_hbba_subscriber hbba_lite_cpp) +install(TARGETS test_on_off_hbba_subscriber DESTINATION lib/${PROJECT_NAME}) + +add_executable(test_throttling_hbba_publisher src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp) +ament_target_dependencies(test_throttling_hbba_publisher rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(test_throttling_hbba_publisher hbba_lite_cpp) +install(TARGETS test_throttling_hbba_publisher DESTINATION lib/${PROJECT_NAME}) + +add_executable(test_throttling_hbba_subscriber src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp) +ament_target_dependencies(test_throttling_hbba_subscriber rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) +target_link_libraries(test_throttling_hbba_subscriber hbba_lite_cpp) +install(TARGETS test_throttling_hbba_subscriber DESTINATION lib/${PROJECT_NAME}) + + +# Python Librairies +ament_python_install_package(${PROJECT_NAME}) + +# Python Nodes +install(PROGRAMS + scripts/dummy_synchronized_publishers.py + scripts/test_arbitration_publisher.py + scripts/test_on_off_hbba_approximate_time_synchronizer.py + scripts/test_on_off_hbba_publisher.py + scripts/test_on_off_hbba_subscriber.py + scripts/test_on_off_hbba_time_synchronizer.py + scripts/test_throttling_hbba_approximate_time_synchronizer.py + scripts/test_throttling_hbba_publisher.py + scripts/test_throttling_hbba_subscriber.py + scripts/test_throttling_hbba_time_synchronizer.py + DESTINATION lib/${PROJECT_NAME} +) + +# Launch files +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) + +# Tests +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_add_gtest(${PROJECT_NAME}_test + test/hbba_lite_cpp/core/DesireTests.cpp + test/hbba_lite_cpp/core/DesireSetTests.cpp + test/hbba_lite_cpp/core/StrategyTests.cpp + test/hbba_lite_cpp/core/SolverTests.cpp + test/hbba_lite_cpp/core/GecodeSolverTests.cpp + test/hbba_lite_cpp/core/HbbaLiteTests.cpp + test/hbba_lite_cpp/main.cpp + ) + ament_target_dependencies(${PROJECT_NAME}_test rclcpp std_msgs hbba_lite_msgs hbba_lite_srvs) + target_link_libraries(${PROJECT_NAME}_test hbba_lite_cpp) +endif() + + +ament_package() diff --git a/src/hbba_lite/__init__.py b/hbba_lite/hbba_lite/__init__.py similarity index 100% rename from src/hbba_lite/__init__.py rename to hbba_lite/hbba_lite/__init__.py diff --git a/src/hbba_lite/filter_states.py b/hbba_lite/hbba_lite/filter_states.py similarity index 78% rename from src/hbba_lite/filter_states.py rename to hbba_lite/hbba_lite/filter_states.py index 8e2ca13..c4eeb5e 100644 --- a/src/hbba_lite/filter_states.py +++ b/hbba_lite/hbba_lite/filter_states.py @@ -1,9 +1,6 @@ from abc import ABC, abstractmethod -import rospy - -from hbba_lite.srv import SetOnOffFilterState, SetOnOffFilterStateResponse, SetThrottlingFilterState, \ - SetThrottlingFilterStateResponse +from hbba_lite_srvs.srv import SetOnOffFilterState, SetThrottlingFilterState class _HbbaFilterState(ABC): @@ -17,13 +14,13 @@ def on_changed(self, callback): class OnOffHbbaFilterState(_HbbaFilterState): - def __init__(self, state_service_name): - self._state_service = rospy.Service(state_service_name, SetOnOffFilterState, self._state_service_callback) + def __init__(self, node, state_service_name): + self._state_service = node.create_service(SetOnOffFilterState, state_service_name, self._state_service_callback) self._is_filtering_all_messages = True self._on_changing_callback = None self._on_changed_callback = None - def _state_service_callback(self, request): + def _state_service_callback(self, request, response): previous_is_filtering_all_messages = self._is_filtering_all_messages if self._on_changing_callback is not None: self._on_changing_callback(previous_is_filtering_all_messages, request.is_filtering_all_messages) @@ -33,7 +30,8 @@ def _state_service_callback(self, request): if self._on_changed_callback is not None: self._on_changed_callback(previous_is_filtering_all_messages, self._is_filtering_all_messages) - return SetOnOffFilterStateResponse(ok=True) + response.ok = True + return response def on_changing(self, callback): self._on_changing_callback = callback @@ -50,17 +48,18 @@ def is_filtering_all_messages(self): class ThrottlingHbbaFilterState(_HbbaFilterState): - def __init__(self, state_service_name): - self._state_service = rospy.Service(state_service_name, SetThrottlingFilterState, self._state_service_callback) + def __init__(self, node, state_service_name): + self._state_service = node.create_service(SetThrottlingFilterState, state_service_name, self._state_service_callback) self._is_filtering_all_messages = True self._rate = 1 self._counter = 0 self._on_changing_callback = None self._on_changed_callback = None - def _state_service_callback(self, request): + def _state_service_callback(self, request, response): if request.rate <= 0: - return SetThrottlingFilterStateResponse(ok=False) + response.ok = False + return response previous_is_filtering_all_messages = self._is_filtering_all_messages previous_rate = self._rate @@ -75,7 +74,8 @@ def _state_service_callback(self, request): self._on_changed_callback(previous_is_filtering_all_messages, self._is_filtering_all_messages, previous_rate, self._rate) - return SetThrottlingFilterStateResponse(ok=True) + response.ok = True + return response def on_changing(self, callback): self._on_changing_callback = callback diff --git a/src/hbba_lite/publishers.py b/hbba_lite/hbba_lite/publishers.py similarity index 55% rename from src/hbba_lite/publishers.py rename to hbba_lite/hbba_lite/publishers.py index 57d2dc0..e3297c1 100644 --- a/src/hbba_lite/publishers.py +++ b/hbba_lite/hbba_lite/publishers.py @@ -1,15 +1,13 @@ -import rospy - from hbba_lite.filter_states import OnOffHbbaFilterState, ThrottlingHbbaFilterState class _HbbaPublisher: - def __init__(self, topic_name, data_class, filter_state_class, state_service_name, queue_size): + def __init__(self, node, data_class, topic_name, filter_state_class, state_service_name, qos_profile): if state_service_name is None: state_service_name = topic_name + '/filter_state' - self._filter_state = filter_state_class(state_service_name) - self._publisher = rospy.Publisher(topic_name, data_class, queue_size=queue_size) + self._filter_state = filter_state_class(node, state_service_name) + self._publisher = node.create_publisher(data_class, topic_name, qos_profile) def publish(self, msg): if self._filter_state.check(): @@ -33,12 +31,14 @@ def on_filter_state_changed(self, callback): class OnOffHbbaPublisher(_HbbaPublisher): - def __init__(self, topic_name, data_class, state_service_name=None, queue_size=None): - super(OnOffHbbaPublisher, self).__init__(topic_name, data_class, OnOffHbbaFilterState, - state_service_name, queue_size) + def __init__(self, node, data_class, topic_name, qos_profile, state_service_name=None): + super(OnOffHbbaPublisher, self).__init__(node, + data_class, topic_name, OnOffHbbaFilterState, + state_service_name, qos_profile) class ThrottlingHbbaPublisher(_HbbaPublisher): - def __init__(self, topic_name, data_class, callback=None, state_service_name=None, queue_size=None): - super(ThrottlingHbbaPublisher, self).__init__(topic_name, data_class, ThrottlingHbbaFilterState, - state_service_name, queue_size) + def __init__(self, node, data_class, topic_name, qos_profile, state_service_name=None): + super(ThrottlingHbbaPublisher, self).__init__(node, + data_class, topic_name, ThrottlingHbbaFilterState, + state_service_name, qos_profile) diff --git a/src/hbba_lite/subscribers.py b/hbba_lite/hbba_lite/subscribers.py similarity index 61% rename from src/hbba_lite/subscribers.py rename to hbba_lite/hbba_lite/subscribers.py index 5a46dc0..85317f7 100644 --- a/src/hbba_lite/subscribers.py +++ b/hbba_lite/hbba_lite/subscribers.py @@ -1,17 +1,16 @@ -import rospy import message_filters from hbba_lite.filter_states import OnOffHbbaFilterState, ThrottlingHbbaFilterState class _HbbaSubscriber: - def __init__(self, topic_name, data_class, filter_state_class, callback, state_service_name, queue_size): + def __init__(self, node, data_class, topic_name, filter_state_class, callback, state_service_name, qos_profile): if state_service_name is None: state_service_name = topic_name + '/filter_state' self._callback = callback - self._filter_state = filter_state_class(state_service_name) - self._subscriber = rospy.Subscriber(topic_name, data_class, self._subscriber_callback, queue_size=queue_size) + self._filter_state = filter_state_class(node, state_service_name) + self._subscriber = node.create_subscription(data_class, topic_name, self._subscriber_callback, qos_profile) def _subscriber_callback(self, msg): if self._filter_state.check() and self._callback is not None: @@ -24,28 +23,30 @@ def is_filtering_all_messages(self): def on_filter_state_changed(self, callback): self._filter_state.on_changed(callback) - def unregister(self): - self._subscriber.unregister() + def destroy(self): + self._subscriber.destroy() class OnOffHbbaSubscriber(_HbbaSubscriber): - def __init__(self, topic_name, data_class, callback=None, state_service_name=None, queue_size=None): - super(OnOffHbbaSubscriber, self).__init__(topic_name, data_class, OnOffHbbaFilterState, - callback, state_service_name, queue_size) + def __init__(self, node, data_class, topic_name, callback, qos_profile, state_service_name=None): + super(OnOffHbbaSubscriber, self).__init__(node, + data_class, topic_name, OnOffHbbaFilterState, + callback, state_service_name, qos_profile) class ThrottlingHbbaSubscriber(_HbbaSubscriber): - def __init__(self, topic_name, data_class, callback=None, state_service_name=None, queue_size=None): - super(ThrottlingHbbaSubscriber, self).__init__(topic_name, data_class, ThrottlingHbbaFilterState, - callback, state_service_name, queue_size) + def __init__(self, node, data_class, topic_name, callback, qos_profile, state_service_name=None): + super(ThrottlingHbbaSubscriber, self).__init__(node, + data_class, topic_name, ThrottlingHbbaFilterState, + callback, state_service_name, qos_profile) class _HbbaTimeSynchronizer: - def __init__(self, message_filter_subscribers, filter_state_class, callback, state_service_name, + def __init__(self, node, message_filter_subscribers, filter_state_class, callback, state_service_name, queue_size): self._callback = callback - self._filter_state = filter_state_class(state_service_name) + self._filter_state = filter_state_class(node, state_service_name) self._ts = message_filters.TimeSynchronizer(message_filter_subscribers, queue_size=queue_size) self._ts.registerCallback(self._ts_callback) @@ -62,23 +63,25 @@ def on_filter_state_changed(self, callback): class OnOffHbbaTimeSynchronizer(_HbbaTimeSynchronizer): - def __init__(self, message_filter_subscribers, queue_size, callback=None, state_service_name=None): - super(OnOffHbbaTimeSynchronizer, self).__init__(message_filter_subscribers, OnOffHbbaFilterState, + def __init__(self, node, message_filter_subscribers, queue_size, callback=None, state_service_name=None): + super(OnOffHbbaTimeSynchronizer, self).__init__(node, + message_filter_subscribers, OnOffHbbaFilterState, callback, state_service_name, queue_size) class ThrottlingHbbaTimeSynchronizer(_HbbaTimeSynchronizer): - def __init__(self, message_filter_subscribers, queue_size, callback=None, state_service_name=None): - super(ThrottlingHbbaTimeSynchronizer, self).__init__(message_filter_subscribers, ThrottlingHbbaFilterState, + def __init__(self, node, message_filter_subscribers, queue_size, callback=None, state_service_name=None): + super(ThrottlingHbbaTimeSynchronizer, self).__init__(node, + message_filter_subscribers, ThrottlingHbbaFilterState, callback, state_service_name, queue_size) class _HbbaApproximateTimeSynchronizer: - def __init__(self, message_filter_subscribers, filter_state_class, callback, state_service_name, + def __init__(self, node, message_filter_subscribers, filter_state_class, callback, state_service_name, queue_size, slop, allow_headerless): self._callback = callback - self._filter_state = filter_state_class(state_service_name) + self._filter_state = filter_state_class(node, state_service_name) self._ts = message_filters.ApproximateTimeSynchronizer(message_filter_subscribers, queue_size, slop, allow_headerless=allow_headerless) self._ts.registerCallback(self._ts_callback) @@ -96,18 +99,20 @@ def on_filter_state_changed(self, callback): class OnOffHbbaApproximateTimeSynchronizer(_HbbaApproximateTimeSynchronizer): - def __init__(self, message_filter_subscribers, queue_size, slop, callback=None, state_service_name=None, + def __init__(self, node, message_filter_subscribers, queue_size, slop, callback=None, state_service_name=None, allow_headerless=False): - super(OnOffHbbaApproximateTimeSynchronizer, self).__init__(message_filter_subscribers, + super(OnOffHbbaApproximateTimeSynchronizer, self).__init__(node, + message_filter_subscribers, OnOffHbbaFilterState, callback, state_service_name, queue_size, slop, allow_headerless) class ThrottlingHbbaApproximateTimeSynchronizer(_HbbaApproximateTimeSynchronizer): - def __init__(self, message_filter_subscribers, queue_size, slop, callback=None, state_service_name=None, + def __init__(self, node, message_filter_subscribers, queue_size, slop, callback=None, state_service_name=None, allow_headerless=False): - super(ThrottlingHbbaApproximateTimeSynchronizer, self).__init__(message_filter_subscribers, + super(ThrottlingHbbaApproximateTimeSynchronizer, self).__init__(node, + message_filter_subscribers, ThrottlingHbbaFilterState, callback, state_service_name, queue_size, slop, allow_headerless) diff --git a/include/hbba_lite/core/Desire.h b/hbba_lite/include/hbba_lite/core/Desire.h similarity index 77% rename from include/hbba_lite/core/Desire.h rename to hbba_lite/include/hbba_lite/core/Desire.h index 0b72a47..afbfda0 100644 --- a/include/hbba_lite/core/Desire.h +++ b/hbba_lite/include/hbba_lite/core/Desire.h @@ -93,8 +93,14 @@ namespace std } #define DECLARE_DESIRE_METHODS(className) \ - std::unique_ptr clone() override { return std::make_unique(*this); } \ - DesireType type() override { return DesireType::get(); } + std::unique_ptr clone() override \ + { \ + return std::make_unique(*this); \ + } \ + DesireType type() override \ + { \ + return DesireType::get(); \ + } class Desire { diff --git a/include/hbba_lite/core/DesireSet.h b/hbba_lite/include/hbba_lite/core/DesireSet.h similarity index 100% rename from include/hbba_lite/core/DesireSet.h rename to hbba_lite/include/hbba_lite/core/DesireSet.h diff --git a/include/hbba_lite/core/GecodeSolver.h b/hbba_lite/include/hbba_lite/core/GecodeSolver.h similarity index 100% rename from include/hbba_lite/core/GecodeSolver.h rename to hbba_lite/include/hbba_lite/core/GecodeSolver.h diff --git a/include/hbba_lite/core/HbbaLite.h b/hbba_lite/include/hbba_lite/core/HbbaLite.h similarity index 97% rename from include/hbba_lite/core/HbbaLite.h rename to hbba_lite/include/hbba_lite/core/HbbaLite.h index abe8262..3425a7c 100644 --- a/include/hbba_lite/core/HbbaLite.h +++ b/hbba_lite/include/hbba_lite/core/HbbaLite.h @@ -40,7 +40,7 @@ class HbbaLite : public DesireSetObserver std::unique_ptr m_strategyStateLogger; std::mutex m_pendingDesiresMutex; - sem_t m_pendingDesiresSemaphore; // TODO remplace with C++20 semaphore + sem_t m_pendingDesiresSemaphore; // TODO remplace with C++20 semaphore std::optional>> m_pendingDesires; std::atomic_bool m_stopped; diff --git a/include/hbba_lite/core/Motivation.h b/hbba_lite/include/hbba_lite/core/Motivation.h similarity index 100% rename from include/hbba_lite/core/Motivation.h rename to hbba_lite/include/hbba_lite/core/Motivation.h diff --git a/include/hbba_lite/core/RosFilterPool.h b/hbba_lite/include/hbba_lite/core/RosFilterPool.h similarity index 54% rename from include/hbba_lite/core/RosFilterPool.h rename to hbba_lite/include/hbba_lite/core/RosFilterPool.h index ad423e9..fec4c62 100644 --- a/include/hbba_lite/core/RosFilterPool.h +++ b/hbba_lite/include/hbba_lite/core/RosFilterPool.h @@ -3,19 +3,19 @@ #include -#include +#include #include class RosFilterPool : public FilterPool { - ros::NodeHandle& m_nodeHandle; + std::shared_ptr m_node; bool m_waitForService; - std::unordered_map m_serviceClientsByName; + std::unordered_map m_serviceClientsByName; public: - RosFilterPool(ros::NodeHandle& nodeHandle, bool waitForService); + RosFilterPool(std::shared_ptr node, bool waitForService); ~RosFilterPool() override = default; DECLARE_NOT_COPYABLE(RosFilterPool); @@ -29,38 +29,40 @@ class RosFilterPool : public FilterPool private: template - void call(const std::string& name, ServiceType& request); + void call(const std::string& name, std::shared_ptr request); }; template -void RosFilterPool::call(const std::string& name, ServiceType& srv) +void RosFilterPool::call(const std::string& name, std::shared_ptr request) { - ros::ServiceClient& service = m_serviceClientsByName[name]; - if (m_waitForService) + auto client = std::dynamic_pointer_cast>(m_serviceClientsByName[name]); + if (client == nullptr) { - ros::service::waitForService(name); + RCLCPP_ERROR(m_node->get_logger(), "The service type is not valid"); + return; } - if (!service.isValid()) - { - service = m_nodeHandle.serviceClient(name, true); - } - if (!service.exists()) + if (m_waitForService) { - ROS_ERROR("The service does not exist (%s)", name.c_str()); + client->wait_for_service(); } - else if (!service.call(srv) || !srv.response.ok) + + auto result = client->async_send_request(request); + result.wait(); + + if (!result.get()->ok) { - ROS_ERROR("The service call has failed (%s)", name.c_str()); + RCLCPP_ERROR(m_node->get_logger(), "The service call has failed (%s)", name.c_str()); } } class RosLogFilterPoolDecorator : public FilterPool { + std::shared_ptr m_node; std::unique_ptr m_filterPool; public: - RosLogFilterPoolDecorator(std::unique_ptr filterPool); + RosLogFilterPoolDecorator(std::shared_ptr node, std::unique_ptr filterPool); ~RosLogFilterPoolDecorator() override = default; DECLARE_NOT_COPYABLE(RosLogFilterPoolDecorator); diff --git a/include/hbba_lite/core/RosStrategyStateLogger.h b/hbba_lite/include/hbba_lite/core/RosStrategyStateLogger.h similarity index 66% rename from include/hbba_lite/core/RosStrategyStateLogger.h rename to hbba_lite/include/hbba_lite/core/RosStrategyStateLogger.h index 2684d3f..a9480ee 100644 --- a/include/hbba_lite/core/RosStrategyStateLogger.h +++ b/hbba_lite/include/hbba_lite/core/RosStrategyStateLogger.h @@ -3,12 +3,16 @@ #include -#include +#include + +#include class RosLogStrategyStateLogger : public StrategyStateLogger { + std::shared_ptr m_node; + public: - RosLogStrategyStateLogger() = default; + explicit RosLogStrategyStateLogger(std::shared_ptr node); ~RosLogStrategyStateLogger() override = default; DECLARE_NOT_COPYABLE(RosLogStrategyStateLogger); @@ -20,11 +24,11 @@ class RosLogStrategyStateLogger : public StrategyStateLogger class RosTopicStrategyStateLogger : public StrategyStateLogger { - ros::NodeHandle& m_nodeHandle; - ros::Publisher m_strategyStatePub; + std::shared_ptr m_node; + rclcpp::Publisher::SharedPtr m_strategyStatePub; public: - RosTopicStrategyStateLogger(ros::NodeHandle& nodeHandle); + explicit RosTopicStrategyStateLogger(std::shared_ptr node); ~RosTopicStrategyStateLogger() override = default; DECLARE_NOT_COPYABLE(RosTopicStrategyStateLogger); diff --git a/include/hbba_lite/core/Solver.h b/hbba_lite/include/hbba_lite/core/Solver.h similarity index 100% rename from include/hbba_lite/core/Solver.h rename to hbba_lite/include/hbba_lite/core/Solver.h diff --git a/include/hbba_lite/core/Strategy.h b/hbba_lite/include/hbba_lite/core/Strategy.h similarity index 100% rename from include/hbba_lite/core/Strategy.h rename to hbba_lite/include/hbba_lite/core/Strategy.h diff --git a/include/hbba_lite/core/StrategyStateLogger.h b/hbba_lite/include/hbba_lite/core/StrategyStateLogger.h similarity index 100% rename from include/hbba_lite/core/StrategyStateLogger.h rename to hbba_lite/include/hbba_lite/core/StrategyStateLogger.h diff --git a/hbba_lite/include/hbba_lite/filters/FilterState.h b/hbba_lite/include/hbba_lite/filters/FilterState.h new file mode 100644 index 0000000..764592b --- /dev/null +++ b/hbba_lite/include/hbba_lite/filters/FilterState.h @@ -0,0 +1,56 @@ +#ifndef HBBA_LITE_FILTERS_FILTER_STATE_H +#define HBBA_LITE_FILTERS_FILTER_STATE_H + +#include +#include +#include + +#include + +class OnOffHbbaFilterState +{ + rclcpp::Service::SharedPtr m_stateService; + bool m_isFilteringAllMessages; + +public: + OnOffHbbaFilterState(const std::shared_ptr& node, const std::string& stateServiceName); + OnOffHbbaFilterState(rclcpp::Node& node, const std::string& stateServiceName); + bool check(); + bool isFilteringAllMessages() const; + +private: + void stateServiceCallback( + const std::shared_ptr request, + std::shared_ptr response); +}; + +inline bool OnOffHbbaFilterState::isFilteringAllMessages() const +{ + return m_isFilteringAllMessages; +} + +class ThrottlingHbbaFilterState +{ + rclcpp::Service::SharedPtr m_stateService; + bool m_isFilteringAllMessages; + int m_rate; + int m_counter; + +public: + ThrottlingHbbaFilterState(const std::shared_ptr& node, const std::string& stateServiceName); + ThrottlingHbbaFilterState(rclcpp::Node& node, const std::string& stateServiceName); + bool check(); + bool isFilteringAllMessages() const; + +private: + void stateServiceCallback( + const std::shared_ptr request, + std::shared_ptr response); +}; + +inline bool ThrottlingHbbaFilterState::isFilteringAllMessages() const +{ + return m_isFilteringAllMessages; +} + +#endif diff --git a/hbba_lite/include/hbba_lite/filters/HbbaFilterNode.h b/hbba_lite/include/hbba_lite/filters/HbbaFilterNode.h new file mode 100644 index 0000000..afb1f7f --- /dev/null +++ b/hbba_lite/include/hbba_lite/filters/HbbaFilterNode.h @@ -0,0 +1,91 @@ +#ifndef HBBA_FILTER_FILTERS_NODE_H +#define HBBA_FILTER_FILTERS_NODE_H + +#include + +#include + +template +class HbbaFilterNode : public rclcpp::Node +{ + std::unique_ptr m_filterState; + + std::string m_inputTopic; + std::string m_outputTopic; + std::string m_stateService; + rclcpp::TimerBase::SharedPtr m_initTimer; + + rclcpp::GenericSubscription::SharedPtr m_subscriber; + rclcpp::GenericPublisher::SharedPtr m_publisher; + +public: + HbbaFilterNode(const std::string& nodeName); + void run(); + +private: + void initTimerCallback(); + void callback(std::shared_ptr); +}; + +template +inline HbbaFilterNode::HbbaFilterNode(const std::string& nodeName) + : rclcpp::Node(nodeName) +{ + m_inputTopic = rclcpp::expand_topic_or_service_name( + declare_parameter("input_topic", "in"), + get_name(), + get_namespace(), + false); + m_outputTopic = rclcpp::expand_topic_or_service_name( + declare_parameter("output_topic", "out"), + get_name(), + get_namespace(), + false); + m_stateService = rclcpp::expand_topic_or_service_name( + declare_parameter("state_service", "filter_state"), + get_name(), + get_namespace(), + true); + + m_initTimer = + create_wall_timer(std::chrono::seconds(1), std::bind(&HbbaFilterNode::initTimerCallback, this)); +} + +template +inline void HbbaFilterNode::run() +{ + rclcpp::spin(shared_from_this()); +} + +template +void HbbaFilterNode::initTimerCallback() +{ + auto all_topics_and_types = get_topic_names_and_types(); + auto it = all_topics_and_types.find(m_inputTopic); + if (it == all_topics_and_types.end() || it->second.empty()) + { + return; + } + + m_filterState = std::make_unique(shared_from_this(), m_stateService); + + m_subscriber = create_generic_subscription( + m_inputTopic, + it->second[0], + 10, + [this](std::shared_ptr msg) + { + if (m_filterState->check()) + { + m_publisher->publish(*msg); + } + }); + m_publisher = create_generic_publisher(m_outputTopic, it->second[0], 10); + + m_initTimer->cancel(); +} + +typedef HbbaFilterNode OnOffHbbaFilterNode; +typedef HbbaFilterNode ThrottlingHbbaFilterNode; + +#endif diff --git a/include/hbba_lite/filters/Publishers.h b/hbba_lite/include/hbba_lite/filters/Publishers.h similarity index 59% rename from include/hbba_lite/filters/Publishers.h rename to hbba_lite/include/hbba_lite/filters/Publishers.h index 0d69d52..51a6891 100644 --- a/include/hbba_lite/filters/Publishers.h +++ b/hbba_lite/include/hbba_lite/filters/Publishers.h @@ -1,7 +1,7 @@ #ifndef HBBA_LITE_FILTERS_PUBLISHERS_H #define HBBA_LITE_FILTERS_PUBLISHERS_H -#include +#include #include @@ -9,20 +9,22 @@ template class HbbaPublisher { FilterState m_filterState; - ros::Publisher m_publisher; + typename rclcpp::Publisher::SharedPtr m_publisher; public: HbbaPublisher( - ros::NodeHandle& nodeHandle, + const std::shared_ptr& node, const std::string& topic, uint32_t queueSize, - const std::string& stateServiceName = "", - bool latch = false); + const std::string& stateServiceName = ""); + HbbaPublisher( + rclcpp::Node& node, + const std::string& topic, + uint32_t queueSize, + const std::string& stateServiceName = ""); uint32_t getNumSubscribers() const; std::string getTopic() const; - bool isLatched() const; - void shutdown(); bool isFilteringAllMessages() const; @@ -31,44 +33,41 @@ class HbbaPublisher template inline HbbaPublisher::HbbaPublisher( - ros::NodeHandle& nodeHandle, + const std::shared_ptr& node, const std::string& topic, uint32_t queueSize, - const std::string& stateServiceName, - bool latch) - : m_filterState(nodeHandle, stateServiceName == "" ? topic + "/filter_state" : stateServiceName) + const std::string& stateServiceName) + : HbbaPublisher(*node, topic, queueSize, stateServiceName) { - m_publisher = nodeHandle.advertise(topic, queueSize, latch); } template -inline uint32_t HbbaPublisher::getNumSubscribers() const +inline HbbaPublisher::HbbaPublisher( + rclcpp::Node& node, + const std::string& topic, + uint32_t queueSize, + const std::string& stateServiceName) + : m_filterState(node, stateServiceName == "" ? topic + "/filter_state" : stateServiceName) { - return m_publisher.getNumSubscribers(); + m_publisher = node.create_publisher(topic, queueSize); } template -inline bool HbbaPublisher::isLatched() const +inline uint32_t HbbaPublisher::getNumSubscribers() const { - return m_publisher.isLatched(); + return m_publisher->get_subscription_count(); } template std::string HbbaPublisher::getTopic() const { - return m_publisher.getTopic(); -} - -template -inline void HbbaPublisher::shutdown() -{ - m_publisher.shutdown(); + return m_publisher->get_topic_name(); } template bool HbbaPublisher::isFilteringAllMessages() const { - return m_filterState.isFilteringAllMessages(); + return m_filterState->isFilteringAllMessages(); } template @@ -76,7 +75,7 @@ inline void HbbaPublisher::publish(const MessageType& { if (m_filterState.check()) { - m_publisher.publish(msg); + m_publisher->publish(msg); } } diff --git a/hbba_lite/include/hbba_lite/filters/Subscribers.h b/hbba_lite/include/hbba_lite/filters/Subscribers.h new file mode 100644 index 0000000..fafeaba --- /dev/null +++ b/hbba_lite/include/hbba_lite/filters/Subscribers.h @@ -0,0 +1,90 @@ +#ifndef HBBA_LITE_FILTERS_SUBSCRIBER_H +#define HBBA_LITE_FILTERS_SUBSCRIBER_H + +#include + +#include + +template +class HbbaSubscriber +{ + FilterState m_filterState; + std::function m_userCallback; + typename rclcpp::Subscription::SharedPtr m_subscriber; + +public: + HbbaSubscriber( + const std::shared_ptr& node, + const std::string& topic, + uint32_t queueSize, + std::function userCallback, + const std::string& stateServiceName = ""); + HbbaSubscriber( + rclcpp::Node& node, + const std::string& topic, + uint32_t queueSize, + std::function userCallback, + const std::string& stateServiceName = ""); + + std::string getTopic() const; + + bool isFilteringAllMessages() const; + +private: + void callback(const typename MessageType::SharedPtr msg); +}; + +template +HbbaSubscriber::HbbaSubscriber( + const std::shared_ptr& node, + const std::string& topic, + uint32_t queueSize, + std::function userCallback, + const std::string& stateServiceName) + : HbbaSubscriber(*node, topic, queueSize, std::move(userCallback), stateServiceName) +{ +} + +template +HbbaSubscriber::HbbaSubscriber( + rclcpp::Node& node, + const std::string& topic, + uint32_t queueSize, + std::function userCallback, + const std::string& stateServiceName) + : m_filterState(node, stateServiceName == "" ? topic + "/filter_state" : stateServiceName), + m_userCallback(std::move(userCallback)) +{ + m_subscriber = node.create_subscription( + topic, + queueSize, + [this](const typename MessageType::SharedPtr msg) { callback(msg); }); +} + +template +std::string HbbaSubscriber::getTopic() const +{ + return m_subscriber->get_topic_name(); +} +template +bool HbbaSubscriber::isFilteringAllMessages() const +{ + return m_filterState.isFilteringAllMessages(); +} + +template +void HbbaSubscriber::callback(const typename MessageType::SharedPtr msg) +{ + if (m_filterState.check() && m_userCallback) + { + m_userCallback(msg); + } +} + +template +using OnOffHbbaSubscriber = HbbaSubscriber; + +template +using ThrottlingHbbaSubscriber = HbbaSubscriber; + +#endif diff --git a/include/hbba_lite/utils/ClassMacros.h b/hbba_lite/include/hbba_lite/utils/ClassMacros.h similarity index 100% rename from include/hbba_lite/utils/ClassMacros.h rename to hbba_lite/include/hbba_lite/utils/ClassMacros.h diff --git a/include/hbba_lite/utils/HbbaLiteException.h b/hbba_lite/include/hbba_lite/utils/HbbaLiteException.h similarity index 100% rename from include/hbba_lite/utils/HbbaLiteException.h rename to hbba_lite/include/hbba_lite/utils/HbbaLiteException.h diff --git a/hbba_lite/launch/test_arbitration.launch.xml b/hbba_lite/launch/test_arbitration.launch.xml new file mode 100644 index 0000000..5ea7614 --- /dev/null +++ b/hbba_lite/launch/test_arbitration.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/hbba_lite/launch/test_on_off_hbba_filter_node.launch.xml b/hbba_lite/launch/test_on_off_hbba_filter_node.launch.xml new file mode 100644 index 0000000..1babb49 --- /dev/null +++ b/hbba_lite/launch/test_on_off_hbba_filter_node.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/hbba_lite/launch/test_throttling_hbba_filter_node.launch.xml b/hbba_lite/launch/test_throttling_hbba_filter_node.launch.xml new file mode 100644 index 0000000..efc17c4 --- /dev/null +++ b/hbba_lite/launch/test_throttling_hbba_filter_node.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/hbba_lite/package.xml b/hbba_lite/package.xml new file mode 100644 index 0000000..0fe130b --- /dev/null +++ b/hbba_lite/package.xml @@ -0,0 +1,31 @@ + + + + hbba_lite + 0.0.0 + The hbba_lite package + Marc-Antoine Maheux + GPL-3.0 license + + ament_cmake + + rclcpp + rclpy + + std_msgs + hbba_lite_msgs + hbba_lite_srvs + message_filters + + rosidl_default_runtime + ros2launch + rosidl_interface_packages + + ament_lint_auto + ament_lint_common + ament_cmake_gtest + + + ament_cmake + + diff --git a/hbba_lite/scripts/dummy_synchronized_publishers.py b/hbba_lite/scripts/dummy_synchronized_publishers.py new file mode 100755 index 0000000..bb374de --- /dev/null +++ b/hbba_lite/scripts/dummy_synchronized_publishers.py @@ -0,0 +1,50 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +from std_msgs.msg import Header +from hbba_lite_msgs.msg import Int32Stamped + + +def main(): + rclpy.init() + + node = rclpy.node.Node('test_on_off_hbba_publisher') + + pub1 = node.create_publisher(Int32Stamped, 'int_topic_1', 10) + pub2 = node.create_publisher(Int32Stamped, 'int_topic_2', 10) + i = 0 + + def callback(): + nonlocal i + + header = Header() + header.stamp = node.get_clock().now().to_msg() + + msg1 = Int32Stamped() + msg1.header = header + msg1.data = 2 * i + + msg2 = Int32Stamped() + msg2.header = header + msg2.data = 4 * i + + pub1.publish(msg1) + pub2.publish(msg2) + + i += 1 + + timer = node.create_timer(1, callback) + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_arbitration_publisher.py b/hbba_lite/scripts/test_arbitration_publisher.py new file mode 100755 index 0000000..d8fca0b --- /dev/null +++ b/hbba_lite/scripts/test_arbitration_publisher.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +from std_msgs.msg import String + + +def main(): + rclpy.init() + + node = rclpy.node.Node('test_arbitration_publisher') + pub = node.create_publisher(String, 'cmd', 10) + rate = node.declare_parameter('rate', 1.0).get_parameter_value().double_value + + def callback(): + msg = String() + msg.data = node.get_name() + pub.publish(msg) + + timer = node.create_timer(1 / rate, callback) + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_on_off_hbba_approximate_time_synchronizer.py b/hbba_lite/scripts/test_on_off_hbba_approximate_time_synchronizer.py new file mode 100755 index 0000000..92a1306 --- /dev/null +++ b/hbba_lite/scripts/test_on_off_hbba_approximate_time_synchronizer.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +import message_filters + +from hbba_lite_msgs.msg import Int32Stamped + +import hbba_lite + + +def main(): + rclpy.init() + node = rclpy.node.Node('test_on_off_hbba_approximate_time_synchronizer') + + def callback(data1, data2): + node.get_logger().info('Data received : {} {}'.format(data1.data, data2.data)) + + sub1 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_1') + sub2 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_2') + + _ = hbba_lite.OnOffHbbaApproximateTimeSynchronizer(node, [sub1, sub2], 10, 0.1, callback, 'int_topics/filter_state') + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_on_off_hbba_publisher.py b/hbba_lite/scripts/test_on_off_hbba_publisher.py new file mode 100755 index 0000000..69bcfd6 --- /dev/null +++ b/hbba_lite/scripts/test_on_off_hbba_publisher.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +from std_msgs.msg import Int8 + +import hbba_lite + + +def main(): + rclpy.init() + + node = rclpy.node.Node('test_on_off_hbba_publisher') + pub = hbba_lite.OnOffHbbaPublisher(node, Int8, 'int_topic_1', 10) + + i = 0 + + def callback(): + nonlocal i + + msg = Int8() + msg.data = i + pub.publish(msg) + + i += 1 + + timer = node.create_timer(1, callback) + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_on_off_hbba_subscriber.py b/hbba_lite/scripts/test_on_off_hbba_subscriber.py new file mode 100755 index 0000000..3f0d474 --- /dev/null +++ b/hbba_lite/scripts/test_on_off_hbba_subscriber.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +from hbba_lite_msgs.msg import Int32Stamped + +import hbba_lite + + +def main(): + rclpy.init() + node = rclpy.node.Node('test_on_off_hbba_subscriber') + + def callback(data): + node.get_logger().info('Data received : {}'.format(data.data)) + + _ = hbba_lite.OnOffHbbaSubscriber(node, Int32Stamped, 'int_topic_1', callback, 10) + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_on_off_hbba_time_synchronizer.py b/hbba_lite/scripts/test_on_off_hbba_time_synchronizer.py new file mode 100755 index 0000000..c058a4d --- /dev/null +++ b/hbba_lite/scripts/test_on_off_hbba_time_synchronizer.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +import message_filters + +from hbba_lite_msgs.msg import Int32Stamped + +import hbba_lite + + +def main(): + rclpy.init() + node = rclpy.node.Node('test_on_off_hbba_time_synchronizer') + + def callback(data1, data2): + node.get_logger().info('Data received : {} {}'.format(data1.data, data2.data)) + + sub1 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_1') + sub2 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_2') + _ = hbba_lite.OnOffHbbaTimeSynchronizer(node, [sub1, sub2], 10, callback, 'int_topics/filter_state') + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_throttling_hbba_approximate_time_synchronizer.py b/hbba_lite/scripts/test_throttling_hbba_approximate_time_synchronizer.py new file mode 100755 index 0000000..adec182 --- /dev/null +++ b/hbba_lite/scripts/test_throttling_hbba_approximate_time_synchronizer.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +import message_filters + +from hbba_lite_msgs.msg import Int32Stamped + +import hbba_lite + + +def main(): + rclpy.init() + node = rclpy.node.Node('test_throttling_hbba_approximate_time_synchronizer') + + def callback(data1, data2): + node.get_logger().info('Data received : {} {}'.format(data1.data, data2.data)) + + sub1 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_1') + sub2 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_2') + _ = hbba_lite.ThrottlingHbbaApproximateTimeSynchronizer(node, [sub1, sub2], 10, 0.1, callback, 'int_topics/filter_state') + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_throttling_hbba_publisher.py b/hbba_lite/scripts/test_throttling_hbba_publisher.py new file mode 100755 index 0000000..abc5162 --- /dev/null +++ b/hbba_lite/scripts/test_throttling_hbba_publisher.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +from std_msgs.msg import Int8 + +import hbba_lite + + +def main(): + rclpy.init() + + node = rclpy.node.Node('test_throttling_hbba_publisher') + pub = hbba_lite.ThrottlingHbbaPublisher(node, Int8, 'int_topic_1', 10) + + i = 0 + + def callback(): + nonlocal i + + msg = Int8() + msg.data = i + pub.publish(msg) + + i += 1 + + timer = node.create_timer(1, callback) + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_throttling_hbba_subscriber.py b/hbba_lite/scripts/test_throttling_hbba_subscriber.py new file mode 100755 index 0000000..9e72296 --- /dev/null +++ b/hbba_lite/scripts/test_throttling_hbba_subscriber.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +from hbba_lite_msgs.msg import Int32Stamped + +import hbba_lite + + +def main(): + rclpy.init() + node = rclpy.node.Node('test_throttling_hbba_subscriber') + + def callback(data): + node.get_logger().info('Data received : {}'.format(data.data)) + + _ = hbba_lite.ThrottlingHbbaSubscriber(node, Int32Stamped, 'int_topic_1', callback, 10) + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/scripts/test_throttling_hbba_time_synchronizer.py b/hbba_lite/scripts/test_throttling_hbba_time_synchronizer.py new file mode 100755 index 0000000..9e09ddc --- /dev/null +++ b/hbba_lite/scripts/test_throttling_hbba_time_synchronizer.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python3 +import rclpy +import rclpy.node + +import message_filters + +from hbba_lite_msgs.msg import Int32Stamped + +import hbba_lite + + +def main(): + rclpy.init() + node = rclpy.node.Node('test_throttling_hbba_time_synchronizer') + + def callback(data1, data2): + node.get_logger().info('Data received : {} {}'.format(data1.data, data2.data)) + + sub1 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_1') + sub2 = message_filters.Subscriber(node, Int32Stamped, 'int_topic_2') + _ = hbba_lite.ThrottlingHbbaTimeSynchronizer(node, [sub1, sub2], 10, callback, 'int_topics/filter_state') + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/hbba_lite/src/arbitration_node.cpp b/hbba_lite/src/arbitration_node.cpp new file mode 100644 index 0000000..eac5a63 --- /dev/null +++ b/hbba_lite/src/arbitration_node.cpp @@ -0,0 +1,149 @@ +#include + +#include +#include + +using namespace std; + +constexpr const char* NODE_NAME = "arbitration_node"; + +struct Topic +{ + string name; + int priority; + rclcpp::Duration timeout; +}; + +class ArbitrationNode : public rclcpp::Node +{ + rclcpp::TimerBase::SharedPtr m_initTimer; + vector m_subscribers; + rclcpp::GenericPublisher::SharedPtr m_publisher; + + vector m_topics; + + optional m_currentTopicIndex; + rclcpp::Time m_lastMessageTime; + +public: + ArbitrationNode() : rclcpp::Node(NODE_NAME), m_lastMessageTime(get_clock()->now()) + { + m_topics = convertToTopics( + declare_parameter("topics", vector{}), + declare_parameter("priorities", vector{}), + declare_parameter("timeout_s", vector{})); + if (!hasUniquePriority(m_topics)) + { + throw std::runtime_error("The topic priorities must be unique."); + } + + m_initTimer = create_wall_timer(std::chrono::seconds(1), std::bind(&ArbitrationNode::initTimerCallback, this)); + } + + void run() { rclcpp::spin(shared_from_this()); } + +private: + vector + convertToTopics(const vector& topics, const vector& priorities, const vector& timeoutS) + { + if (topics.size() != priorities.size() || topics.size() != timeoutS.size()) + { + throw std::runtime_error("The topics, priorities, timeout_s parameters must have the same size."); + } + + vector convertedTopics; + for (size_t i = 0; i < topics.size(); i++) + { + auto expandedTopic = rclcpp::expand_topic_or_service_name(topics[i], get_name(), get_namespace(), false); + auto timeout = chrono::duration>(timeoutS[i]); + convertedTopics.emplace_back(Topic{expandedTopic, static_cast(priorities[i]), timeout}); + } + + return convertedTopics; + } + + bool hasUniquePriority(const vector& topics) + { + unordered_set priorities; + + for (auto& topic : topics) + { + if (priorities.count(topic.priority) > 0) + { + return false; + } + + priorities.insert(topic.priority); + } + + return true; + } + + void initTimerCallback() + { + auto topicType = getTopicType(); + if (topicType == nullopt) + { + return; + } + + for (size_t i = 0; i < m_topics.size(); i++) + { + m_subscribers.emplace_back(create_generic_subscription( + m_topics[i].name, + *topicType, + 1, + [this, i](shared_ptr msg) { messageCallback(i, msg); })); + } + m_publisher = create_generic_publisher("out", *topicType, 10); + + m_initTimer->cancel(); + } + + optional getTopicType() + { + auto all_topics_and_types = get_topic_names_and_types(); + string type; + for (auto t : m_topics) + { + auto it = all_topics_and_types.find(t.name); + if (it != all_topics_and_types.end() && !it->second.empty()) + { + return it->second[0]; + } + } + + return nullopt; + } + + void messageCallback(size_t i, shared_ptr msg) + { + if (m_currentTopicIndex == nullopt || m_topics[i].priority <= m_topics[*m_currentTopicIndex].priority || + (get_clock()->now() - m_lastMessageTime) > m_topics[*m_currentTopicIndex].timeout) + { + m_currentTopicIndex = i; + m_lastMessageTime = get_clock()->now(); + m_publisher->publish(*msg); + } + } +}; + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + try + { + auto node = std::make_shared(); + node->run(); + rclcpp::shutdown(); + } + catch (const std::exception& e) + { + RCLCPP_ERROR(rclcpp::get_logger(NODE_NAME), "%s", e.what()); + rclcpp::shutdown(); + return -1; + } + + return 0; +} diff --git a/src/hbba_lite_cpp/core/Desire.cpp b/hbba_lite/src/hbba_lite_cpp/core/Desire.cpp similarity index 100% rename from src/hbba_lite_cpp/core/Desire.cpp rename to hbba_lite/src/hbba_lite_cpp/core/Desire.cpp diff --git a/src/hbba_lite_cpp/core/DesireSet.cpp b/hbba_lite/src/hbba_lite_cpp/core/DesireSet.cpp similarity index 100% rename from src/hbba_lite_cpp/core/DesireSet.cpp rename to hbba_lite/src/hbba_lite_cpp/core/DesireSet.cpp diff --git a/src/hbba_lite_cpp/core/GecodeSolver.cpp b/hbba_lite/src/hbba_lite_cpp/core/GecodeSolver.cpp similarity index 100% rename from src/hbba_lite_cpp/core/GecodeSolver.cpp rename to hbba_lite/src/hbba_lite_cpp/core/GecodeSolver.cpp diff --git a/src/hbba_lite_cpp/core/HbbaLite.cpp b/hbba_lite/src/hbba_lite_cpp/core/HbbaLite.cpp similarity index 100% rename from src/hbba_lite_cpp/core/HbbaLite.cpp rename to hbba_lite/src/hbba_lite_cpp/core/HbbaLite.cpp diff --git a/src/hbba_lite_cpp/core/Motivation.cpp b/hbba_lite/src/hbba_lite_cpp/core/Motivation.cpp similarity index 100% rename from src/hbba_lite_cpp/core/Motivation.cpp rename to hbba_lite/src/hbba_lite_cpp/core/Motivation.cpp diff --git a/hbba_lite/src/hbba_lite_cpp/core/RosFilterPool.cpp b/hbba_lite/src/hbba_lite_cpp/core/RosFilterPool.cpp new file mode 100644 index 0000000..63dd516 --- /dev/null +++ b/hbba_lite/src/hbba_lite_cpp/core/RosFilterPool.cpp @@ -0,0 +1,125 @@ +#include +#include + +#include +#include + +using namespace std; + +RosFilterPool::RosFilterPool(shared_ptr node, bool waitForService) + : m_node(move(node)), + m_waitForService(waitForService) +{ +} + +void RosFilterPool::add(const string& name, FilterType type) +{ + lock_guard lock(m_mutex); + FilterPool::add(name, type); + + switch (type) + { + case FilterType::ON_OFF: + m_serviceClientsByName[name] = m_node->create_client(name); + break; + + case FilterType::THROTTLING: + m_serviceClientsByName[name] = m_node->create_client(name); + break; + + default: + throw HbbaLiteException("Not supported filter type"); + } +} + +void RosFilterPool::applyEnabling(const string& name, const FilterConfiguration& configuration) +{ + switch (m_typesByName[name]) + { + case FilterType::ON_OFF: + { + auto request = make_shared(); + request->is_filtering_all_messages = false; + call(name, request); + } + break; + + case FilterType::THROTTLING: + { + auto request = make_shared(); + request->is_filtering_all_messages = false; + request->rate = configuration.rate(); + call(name, request); + } + break; + + default: + throw HbbaLiteException("Not supported filter type"); + } +} + +void RosFilterPool::applyDisabling(const string& name) +{ + switch (m_typesByName[name]) + { + case FilterType::ON_OFF: + { + auto request = make_shared(); + request->is_filtering_all_messages = true; + call(name, request); + } + break; + + case FilterType::THROTTLING: + { + auto request = make_shared(); + request->is_filtering_all_messages = true; + request->rate = 1; + call(name, request); + } + break; + + default: + throw HbbaLiteException("Not supported filter type"); + } +} + +RosLogFilterPoolDecorator::RosLogFilterPoolDecorator(shared_ptr node, unique_ptr filterPool) + : m_node(move(node)), + m_filterPool(move(filterPool)) +{ +} + +void RosLogFilterPoolDecorator::add(const string& name, FilterType type) +{ + lock_guard lock(m_mutex); + FilterPool::add(name, type); + m_filterPool->add(name, type); +} + +void RosLogFilterPoolDecorator::applyEnabling(const string& name, const FilterConfiguration& configuration) +{ + callApplyEnabling(*m_filterPool, name, configuration); + + switch (configuration.type()) + { + case FilterType::ON_OFF: + RCLCPP_INFO_STREAM(m_node->get_logger(), "HBBA filter state changed: " << name << " -> enabled"); + break; + + case FilterType::THROTTLING: + RCLCPP_INFO_STREAM( + m_node->get_logger(), + "HBBA filter state changed: " << name << " -> enabled (" << configuration.rate() << ")"); + break; + + default: + throw HbbaLiteException("Not supported filter type"); + } +} + +void RosLogFilterPoolDecorator::applyDisabling(const std::string& name) +{ + callApplyDisabling(*m_filterPool, name); + RCLCPP_INFO_STREAM(m_node->get_logger(), "HBBA filter state changed: " << name << " -> disabled"); +} diff --git a/hbba_lite/src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp b/hbba_lite/src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp new file mode 100644 index 0000000..d38359a --- /dev/null +++ b/hbba_lite/src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp @@ -0,0 +1,29 @@ +#include + +using namespace std; + +RosLogStrategyStateLogger::RosLogStrategyStateLogger(std::shared_ptr node) : m_node(move(node)) {} + +void RosLogStrategyStateLogger::log(DesireType desireType, StrategyType strategyType, bool enabled) +{ + RCLCPP_INFO_STREAM( + m_node->get_logger(), + "HBBA strategy state changed: " + << "( " << desireType.name() << ", " << strategyType.name() << ") -> " + << (enabled ? "enabled" : "disabled")); +} + + +RosTopicStrategyStateLogger::RosTopicStrategyStateLogger(std::shared_ptr node) : m_node(move(node)) +{ + m_strategyStatePub = m_node->create_publisher("hbba_strategy_state_log", 1000); +} + +void RosTopicStrategyStateLogger::log(DesireType desireType, StrategyType strategyType, bool enabled) +{ + hbba_lite_msgs::msg::StrategyState msg; + msg.desire_type_name = desireType.name(); + msg.strategy_type_name = strategyType.name(); + msg.enabled = enabled; + m_strategyStatePub->publish(msg); +} diff --git a/src/hbba_lite_cpp/core/Solver.cpp b/hbba_lite/src/hbba_lite_cpp/core/Solver.cpp similarity index 100% rename from src/hbba_lite_cpp/core/Solver.cpp rename to hbba_lite/src/hbba_lite_cpp/core/Solver.cpp diff --git a/src/hbba_lite_cpp/core/Strategy.cpp b/hbba_lite/src/hbba_lite_cpp/core/Strategy.cpp similarity index 100% rename from src/hbba_lite_cpp/core/Strategy.cpp rename to hbba_lite/src/hbba_lite_cpp/core/Strategy.cpp diff --git a/src/hbba_lite_cpp/core/StrategyStateLogger.cpp b/hbba_lite/src/hbba_lite_cpp/core/StrategyStateLogger.cpp similarity index 100% rename from src/hbba_lite_cpp/core/StrategyStateLogger.cpp rename to hbba_lite/src/hbba_lite_cpp/core/StrategyStateLogger.cpp diff --git a/hbba_lite/src/hbba_lite_cpp/filters/FilterState.cpp b/hbba_lite/src/hbba_lite_cpp/filters/FilterState.cpp new file mode 100644 index 0000000..204c6a9 --- /dev/null +++ b/hbba_lite/src/hbba_lite_cpp/filters/FilterState.cpp @@ -0,0 +1,84 @@ +#include + +using namespace std; + +OnOffHbbaFilterState::OnOffHbbaFilterState(const shared_ptr& node, const string& stateServiceName) + : OnOffHbbaFilterState(*node, stateServiceName) +{ +} + +OnOffHbbaFilterState::OnOffHbbaFilterState(rclcpp::Node& node, const string& stateServiceName) + : m_isFilteringAllMessages(true) +{ + using namespace std::placeholders; + m_stateService = node.create_service( + stateServiceName, + bind(&OnOffHbbaFilterState::stateServiceCallback, this, _1, _2)); +} + +bool OnOffHbbaFilterState::check() +{ + return !m_isFilteringAllMessages; +} + +void OnOffHbbaFilterState::stateServiceCallback( + const shared_ptr request, + shared_ptr response) +{ + m_isFilteringAllMessages = request->is_filtering_all_messages; + response->ok = true; +} + +ThrottlingHbbaFilterState::ThrottlingHbbaFilterState( + const shared_ptr& node, + const string& stateServiceName) + : ThrottlingHbbaFilterState(*node, stateServiceName) +{ +} + +ThrottlingHbbaFilterState::ThrottlingHbbaFilterState( + rclcpp::Node& node, + const string& stateServiceName) + : m_isFilteringAllMessages(true), + m_rate(1), + m_counter(0) +{ + using namespace std::placeholders; + m_stateService = node.create_service( + stateServiceName, + bind(&ThrottlingHbbaFilterState::stateServiceCallback, this, _1, _2)); +} + +bool ThrottlingHbbaFilterState::check() +{ + if (m_isFilteringAllMessages) + { + return false; + } + + bool isReady = false; + if (m_counter == 0) + { + isReady = true; + } + m_counter = (m_counter + 1) % m_rate; + return isReady; +} + +void ThrottlingHbbaFilterState::stateServiceCallback( + const shared_ptr request, + shared_ptr response) +{ + if (request->rate <= 0) + { + response->ok = false; + } + else + { + m_isFilteringAllMessages = request->is_filtering_all_messages; + m_rate = request->rate; + m_counter = 0; + + response->ok = true; + } +} diff --git a/src/hbba_lite_cpp/utils/HbbaLiteException.cpp b/hbba_lite/src/hbba_lite_cpp/utils/HbbaLiteException.cpp similarity index 100% rename from src/hbba_lite_cpp/utils/HbbaLiteException.cpp rename to hbba_lite/src/hbba_lite_cpp/utils/HbbaLiteException.cpp diff --git a/hbba_lite/src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp b/hbba_lite/src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp new file mode 100644 index 0000000..66b9ac2 --- /dev/null +++ b/hbba_lite/src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp @@ -0,0 +1,27 @@ +#include +#include + +#include + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + auto node = rclcpp::Node::make_shared("test_on_off_hbba_publisher"); + OnOffHbbaPublisher pub(node, "int_topic", 10); + + rclcpp::Rate rate(1); + for (int i = 0; rclcpp::ok(); i++) + { + std_msgs::msg::Int8 msg; + msg.data = i; + pub.publish(msg); + + rclcpp::spin_some(node); + rate.sleep(); + } + + rclcpp::shutdown(); + + return 0; +} diff --git a/hbba_lite/src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp b/hbba_lite/src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp new file mode 100644 index 0000000..4caa58e --- /dev/null +++ b/hbba_lite/src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp @@ -0,0 +1,22 @@ +#include + +#include +#include + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + auto node = rclcpp::Node::make_shared("test_on_off_hbba_subscriber"); + OnOffHbbaSubscriber sub( + node, + "int_topic_1", + 10, + [node](const hbba_lite_msgs::msg::Int32Stamped::SharedPtr msg) + { RCLCPP_INFO(node->get_logger(), "Data received : %i", static_cast(msg->data)); }); + + rclcpp::spin(node); + rclcpp::shutdown(); + + return 0; +} diff --git a/hbba_lite/src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp b/hbba_lite/src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp new file mode 100644 index 0000000..c8c2afe --- /dev/null +++ b/hbba_lite/src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp @@ -0,0 +1,27 @@ +#include +#include + +#include + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + auto node = rclcpp::Node::make_shared("test_on_off_hbba_publisher"); + ThrottlingHbbaPublisher pub(node, "int_topic", 10); + + rclcpp::Rate rate(1); + for (int i = 0; rclcpp::ok(); i++) + { + std_msgs::msg::Int8 msg; + msg.data = i; + pub.publish(msg); + + rclcpp::spin_some(node); + rate.sleep(); + } + + rclcpp::shutdown(); + + return 0; +} diff --git a/hbba_lite/src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp b/hbba_lite/src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp new file mode 100644 index 0000000..245cff3 --- /dev/null +++ b/hbba_lite/src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp @@ -0,0 +1,22 @@ +#include + +#include +#include + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + auto node = rclcpp::Node::make_shared("test_on_off_hbba_subscriber"); + ThrottlingHbbaSubscriber sub( + node, + "int_topic_1", + 10, + [node](const hbba_lite_msgs::msg::Int32Stamped::SharedPtr msg) + { RCLCPP_INFO(node->get_logger(), "Data received : %i", static_cast(msg->data)); }); + + rclcpp::spin(node); + rclcpp::shutdown(); + + return 0; +} diff --git a/hbba_lite/src/on_off_hbba_filter_node.cpp b/hbba_lite/src/on_off_hbba_filter_node.cpp new file mode 100644 index 0000000..61606c1 --- /dev/null +++ b/hbba_lite/src/on_off_hbba_filter_node.cpp @@ -0,0 +1,15 @@ +#include + +#include + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + auto node = std::make_shared("on_off_hbba_filter_node"); + node->run(); + + rclcpp::shutdown(); + + return 0; +} diff --git a/hbba_lite/src/throttling_hbba_filter_node.cpp b/hbba_lite/src/throttling_hbba_filter_node.cpp new file mode 100644 index 0000000..a417fa9 --- /dev/null +++ b/hbba_lite/src/throttling_hbba_filter_node.cpp @@ -0,0 +1,15 @@ +#include + +#include + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + + auto node = std::make_shared("throttling_hbba_filter_node"); + node->run(); + + rclcpp::shutdown(); + + return 0; +} diff --git a/test/hbba_lite_cpp/core/DesireSetTests.cpp b/hbba_lite/test/hbba_lite_cpp/core/DesireSetTests.cpp similarity index 100% rename from test/hbba_lite_cpp/core/DesireSetTests.cpp rename to hbba_lite/test/hbba_lite_cpp/core/DesireSetTests.cpp diff --git a/test/hbba_lite_cpp/core/DesireTests.cpp b/hbba_lite/test/hbba_lite_cpp/core/DesireTests.cpp similarity index 100% rename from test/hbba_lite_cpp/core/DesireTests.cpp rename to hbba_lite/test/hbba_lite_cpp/core/DesireTests.cpp diff --git a/test/hbba_lite_cpp/core/Desires.h b/hbba_lite/test/hbba_lite_cpp/core/Desires.h similarity index 100% rename from test/hbba_lite_cpp/core/Desires.h rename to hbba_lite/test/hbba_lite_cpp/core/Desires.h diff --git a/test/hbba_lite_cpp/core/FilterPoolMock.h b/hbba_lite/test/hbba_lite_cpp/core/FilterPoolMock.h similarity index 100% rename from test/hbba_lite_cpp/core/FilterPoolMock.h rename to hbba_lite/test/hbba_lite_cpp/core/FilterPoolMock.h diff --git a/test/hbba_lite_cpp/core/GecodeSolverTests.cpp b/hbba_lite/test/hbba_lite_cpp/core/GecodeSolverTests.cpp similarity index 100% rename from test/hbba_lite_cpp/core/GecodeSolverTests.cpp rename to hbba_lite/test/hbba_lite_cpp/core/GecodeSolverTests.cpp diff --git a/test/hbba_lite_cpp/core/HbbaLiteTests.cpp b/hbba_lite/test/hbba_lite_cpp/core/HbbaLiteTests.cpp similarity index 100% rename from test/hbba_lite_cpp/core/HbbaLiteTests.cpp rename to hbba_lite/test/hbba_lite_cpp/core/HbbaLiteTests.cpp diff --git a/test/hbba_lite_cpp/core/SolverTests.cpp b/hbba_lite/test/hbba_lite_cpp/core/SolverTests.cpp similarity index 100% rename from test/hbba_lite_cpp/core/SolverTests.cpp rename to hbba_lite/test/hbba_lite_cpp/core/SolverTests.cpp diff --git a/test/hbba_lite_cpp/core/StrategyTests.cpp b/hbba_lite/test/hbba_lite_cpp/core/StrategyTests.cpp similarity index 100% rename from test/hbba_lite_cpp/core/StrategyTests.cpp rename to hbba_lite/test/hbba_lite_cpp/core/StrategyTests.cpp diff --git a/test/hbba_lite_cpp/main.cpp b/hbba_lite/test/hbba_lite_cpp/main.cpp similarity index 100% rename from test/hbba_lite_cpp/main.cpp rename to hbba_lite/test/hbba_lite_cpp/main.cpp diff --git a/hbba_lite_msgs/CMakeLists.txt b/hbba_lite_msgs/CMakeLists.txt new file mode 100644 index 0000000..cb8b3c5 --- /dev/null +++ b/hbba_lite_msgs/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.5) +project(hbba_lite_msgs) + + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Find dependencies +find_package(ament_cmake REQUIRED) +find_package(std_msgs REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +# Generate messages +rosidl_generate_interfaces(${PROJECT_NAME} + "msg/Int32Stamped.msg" + "msg/StrategyState.msg" + DEPENDENCIES std_msgs +) + +ament_package() diff --git a/hbba_lite_msgs/msg/Int32Stamped.msg b/hbba_lite_msgs/msg/Int32Stamped.msg new file mode 100644 index 0000000..bf748e8 --- /dev/null +++ b/hbba_lite_msgs/msg/Int32Stamped.msg @@ -0,0 +1,2 @@ +std_msgs/Header header +int32 data diff --git a/msg/StrategyState.msg b/hbba_lite_msgs/msg/StrategyState.msg similarity index 100% rename from msg/StrategyState.msg rename to hbba_lite_msgs/msg/StrategyState.msg diff --git a/hbba_lite_msgs/package.xml b/hbba_lite_msgs/package.xml new file mode 100644 index 0000000..a855e35 --- /dev/null +++ b/hbba_lite_msgs/package.xml @@ -0,0 +1,25 @@ + + + + hbba_lite_msgs + 0.0.0 + The hbba_lite_msgs package + Marc-Antoine Maheux + GPL-3.0 license + + ament_cmake + rosidl_default_generators + + std_msgs + + rosidl_default_runtime + rosidl_interface_packages + + ament_lint_auto + ament_lint_common + ament_cmake_gtest + + + ament_cmake + + diff --git a/hbba_lite_srvs/CMakeLists.txt b/hbba_lite_srvs/CMakeLists.txt new file mode 100644 index 0000000..d43a5b8 --- /dev/null +++ b/hbba_lite_srvs/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.5) +project(hbba_lite_srvs) + + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Find dependencies +find_package(ament_cmake REQUIRED) +find_package(std_msgs REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +# Generate services +rosidl_generate_interfaces(${PROJECT_NAME} + "srv/SetOnOffFilterState.srv" + "srv/SetThrottlingFilterState.srv" + DEPENDENCIES std_msgs +) + +ament_package() diff --git a/hbba_lite_srvs/package.xml b/hbba_lite_srvs/package.xml new file mode 100644 index 0000000..3cd2b10 --- /dev/null +++ b/hbba_lite_srvs/package.xml @@ -0,0 +1,25 @@ + + + + hbba_lite_srvs + 0.0.0 + The hbba_lite_srvs package + Marc-Antoine Maheux + GPL-3.0 license + + ament_cmake + rosidl_default_generators + + std_msgs + + rosidl_default_runtime + rosidl_interface_packages + + ament_lint_auto + ament_lint_common + ament_cmake_gtest + + + ament_cmake + + diff --git a/srv/SetOnOffFilterState.srv b/hbba_lite_srvs/srv/SetOnOffFilterState.srv similarity index 100% rename from srv/SetOnOffFilterState.srv rename to hbba_lite_srvs/srv/SetOnOffFilterState.srv diff --git a/srv/SetThrottlingFilterState.srv b/hbba_lite_srvs/srv/SetThrottlingFilterState.srv similarity index 100% rename from srv/SetThrottlingFilterState.srv rename to hbba_lite_srvs/srv/SetThrottlingFilterState.srv diff --git a/include/hbba_lite/filters/FilterState.h b/include/hbba_lite/filters/FilterState.h deleted file mode 100644 index 25326db..0000000 --- a/include/hbba_lite/filters/FilterState.h +++ /dev/null @@ -1,54 +0,0 @@ -#ifndef HBBA_LITE_FILTERS_FILTER_STATE_H -#define HBBA_LITE_FILTERS_FILTER_STATE_H - -#include -#include -#include - -#include - -class OnOffHbbaFilterState -{ - ros::ServiceServer m_stateService; - bool m_isFilteringAllMessages; - -public: - OnOffHbbaFilterState(ros::NodeHandle& nodeHandle, const std::string& stateServiceName); - bool check(); - bool isFilteringAllMessages() const; - -private: - bool stateServiceCallback( - hbba_lite::SetOnOffFilterState::Request& request, - hbba_lite::SetOnOffFilterState::Response& response); -}; - -inline bool OnOffHbbaFilterState::isFilteringAllMessages() const -{ - return m_isFilteringAllMessages; -} - -class ThrottlingHbbaFilterState -{ - ros::ServiceServer m_stateService; - bool m_isFilteringAllMessages; - int m_rate; - int m_counter; - -public: - ThrottlingHbbaFilterState(ros::NodeHandle& nodeHandle, const std::string& stateServiceName); - bool check(); - bool isFilteringAllMessages() const; - -private: - bool stateServiceCallback( - hbba_lite::SetThrottlingFilterState::Request& request, - hbba_lite::SetThrottlingFilterState::Response& response); -}; - -inline bool ThrottlingHbbaFilterState::isFilteringAllMessages() const -{ - return m_isFilteringAllMessages; -} - -#endif diff --git a/include/hbba_lite/filters/HbbaFilterNode.h b/include/hbba_lite/filters/HbbaFilterNode.h deleted file mode 100644 index 3d3ab96..0000000 --- a/include/hbba_lite/filters/HbbaFilterNode.h +++ /dev/null @@ -1,73 +0,0 @@ -#ifndef HBBA_FILTER_FILTERS_NODE_H -#define HBBA_FILTER_FILTERS_NODE_H - -#include -#include - -#include - -// Inspired by https://github.com/ros/ros_comm/blob/indigo-devel/tools/topic_tools/src/relay.cpp -template -class HbbaFilterNode -{ - ros::NodeHandle& m_nodeHandle; - FilterState m_filterState; - ros::Subscriber m_subscriber; - ros::Publisher m_publisher; - bool m_hasAdvertised; - -public: - HbbaFilterNode(ros::NodeHandle& nodeHandle); - void run(); - -private: - void callback(const ros::MessageEvent& msg_event); -}; - -template -inline HbbaFilterNode::HbbaFilterNode(ros::NodeHandle& nodeHandle) - : m_nodeHandle(nodeHandle), - m_filterState(nodeHandle, "filter_state"), - m_hasAdvertised(false) -{ - m_subscriber = nodeHandle.subscribe("in", 10, &HbbaFilterNode::callback, this); -} - -template -inline void HbbaFilterNode::run() -{ - ros::spin(); -} - -template -void HbbaFilterNode::callback(const ros::MessageEvent& msg_event) -{ - boost::shared_ptr const& msg = msg_event.getConstMessage(); - - if (!m_hasAdvertised) - { - boost::shared_ptr const& connectionHeader = msg_event.getConnectionHeaderPtr(); - bool latch = false; - if (connectionHeader) - { - auto it = connectionHeader->find("latching"); - if (it != connectionHeader->end() && it->second == "1") - { - latch = true; - } - } - - m_publisher = msg->advertise(m_nodeHandle, "out", 10, latch); - m_hasAdvertised = true; - } - - if (m_filterState.check()) - { - m_publisher.publish(msg); - } -} - -typedef HbbaFilterNode OnOffHbbaFilterNode; -typedef HbbaFilterNode ThrottlingHbbaFilterNode; - -#endif diff --git a/include/hbba_lite/filters/Subscribers.h b/include/hbba_lite/filters/Subscribers.h deleted file mode 100644 index e22e200..0000000 --- a/include/hbba_lite/filters/Subscribers.h +++ /dev/null @@ -1,116 +0,0 @@ -#ifndef HBBA_LITE_FILTERS_SUBSCRIBER_H -#define HBBA_LITE_FILTERS_SUBSCRIBER_H - -#include - -#include - -template -class HbbaSubscriber -{ - FilterState m_filterState; - boost::function m_callback; - ros::Subscriber m_subscriber; - -public: - template - HbbaSubscriber( - ros::NodeHandle& nodeHandle, - const std::string& topic, - uint32_t queueSize, - void (T::*fp)(const typename MessageType::ConstPtr&), - T* obj, - const std::string& stateServiceName = "", - const ros::TransportHints& transportHints = ros::TransportHints()); - HbbaSubscriber( - ros::NodeHandle& nodeHandle, - const std::string& topic, - uint32_t queueSize, - void (*fp)(const typename MessageType::ConstPtr&), - const std::string& stateServiceName = "", - const ros::TransportHints& transportHints = ros::TransportHints()); - - uint32_t getNumPublishers() const; - std::string getTopic() const; - void shutdown(); - - bool isFilteringAllMessages() const; - -private: - void callback(const typename MessageType::ConstPtr& msg); -}; - -template -template -HbbaSubscriber::HbbaSubscriber( - ros::NodeHandle& nodeHandle, - const std::string& topic, - uint32_t queueSize, - void (T::*fp)(const typename MessageType::ConstPtr&), - T* obj, - const std::string& stateServiceName, - const ros::TransportHints& transportHints) - : m_filterState(nodeHandle, stateServiceName == "" ? topic + "/filter_state" : stateServiceName) -{ - m_callback = boost::bind(fp, obj, _1); - m_subscriber = - nodeHandle - .subscribe(topic, queueSize, &HbbaSubscriber::callback, this, transportHints); -} - -template -HbbaSubscriber::HbbaSubscriber( - ros::NodeHandle& nodeHandle, - const std::string& topic, - uint32_t queueSize, - void (*fp)(const typename MessageType::ConstPtr&), - const std::string& stateServiceName, - const ros::TransportHints& transportHints) - : m_filterState(nodeHandle, stateServiceName == "" ? topic + "/filter_state" : stateServiceName) -{ - m_callback = fp; - m_subscriber = - nodeHandle - .subscribe(topic, queueSize, &HbbaSubscriber::callback, this, transportHints); -} - -template -uint32_t HbbaSubscriber::getNumPublishers() const -{ - return m_subscriber.getNumPublishers(); -} - -template -std::string HbbaSubscriber::getTopic() const -{ - return m_subscriber.getTopic(); -} - -template -void HbbaSubscriber::shutdown() -{ - m_subscriber.shutdown(); -} - -template -bool HbbaSubscriber::isFilteringAllMessages() const -{ - return m_filterState.isFilteringAllMessages(); -} - -template -void HbbaSubscriber::callback(const typename MessageType::ConstPtr& msg) -{ - if (m_filterState.check() && m_callback) - { - m_callback(msg); - } -} - -template -using OnOffHbbaSubscriber = HbbaSubscriber; - -template -using ThrottlingHbbaSubscriber = HbbaSubscriber; - -#endif diff --git a/launch/test_arbitration.launch b/launch/test_arbitration.launch deleted file mode 100644 index 38c94d5..0000000 --- a/launch/test_arbitration.launch +++ /dev/null @@ -1,34 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - name: publisher_1/cmd - priority: 1 - timeout_s: 10.0 - - name: publisher_2/cmd - priority: 2 - timeout_s: 2.0 - - name: publisher_3/cmd - priority: 3 - timeout_s: 1.0 - - - - - - diff --git a/msg/Int32Stamped.msg b/msg/Int32Stamped.msg deleted file mode 100644 index 5b2498f..0000000 --- a/msg/Int32Stamped.msg +++ /dev/null @@ -1,2 +0,0 @@ -Header header -int32 data diff --git a/package.xml b/package.xml deleted file mode 100644 index d41c3d2..0000000 --- a/package.xml +++ /dev/null @@ -1,80 +0,0 @@ - - - hbba_lite - 0.0.0 - The hbba_lite package - - - - - marc-antoine - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - message_generation - message_runtime - roscpp - rospy - message_filters - std_msgs - topic_tools - roscpp - rospy - message_generation - message_runtime - message_filters - std_msgs - topic_tools - roscpp - rospy - message_generation - message_runtime - message_filters - std_msgs - topic_tools - - - - - - - - diff --git a/scripts/hbba_lite_python_tests/dummy_synchronized_publishers.py b/scripts/hbba_lite_python_tests/dummy_synchronized_publishers.py deleted file mode 100755 index 285edf5..0000000 --- a/scripts/hbba_lite_python_tests/dummy_synchronized_publishers.py +++ /dev/null @@ -1,38 +0,0 @@ -#!/usr/bin/env python3 -import rospy - -from std_msgs.msg import Header -from hbba_lite.msg import Int32Stamped - -import hbba_lite - - -def main(): - rospy.init_node('test_on_off_hbba_publisher') - pub1 = rospy.Publisher('int_topic_1', Int32Stamped, queue_size=10) - pub2 = rospy.Publisher('int_topic_2', Int32Stamped, queue_size=10) - - rate = rospy.Rate(1) # 1hz - i = 0 - while not rospy.is_shutdown(): - header = Header() - header.seq = i - header.stamp = rospy.Time.now() - - msg1 = Int32Stamped() - msg1.header = header - msg1.data = 2 * i - - msg2 = Int32Stamped() - msg2.header = header - msg2.data = 4 * i - - pub1.publish(msg1) - pub2.publish(msg2) - - i += 1 - rate.sleep() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_arbitration_publisher.py b/scripts/hbba_lite_python_tests/test_arbitration_publisher.py deleted file mode 100755 index 5b659dd..0000000 --- a/scripts/hbba_lite_python_tests/test_arbitration_publisher.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -import rospy - -from std_msgs.msg import String - - -def main(): - rospy.init_node('test_arbitration_publisher') - pub = rospy.Publisher('cmd', String, queue_size=10) - - rate = rospy.Rate(rospy.get_param('~rate', 1.0)) - while not rospy.is_shutdown(): - - msg = String() - msg.data = rospy.get_name() - pub.publish(msg) - - rate.sleep() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_on_off_hbba_approximate_time_synchronizer.py b/scripts/hbba_lite_python_tests/test_on_off_hbba_approximate_time_synchronizer.py deleted file mode 100755 index dd0e853..0000000 --- a/scripts/hbba_lite_python_tests/test_on_off_hbba_approximate_time_synchronizer.py +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env python3 -import rospy -import message_filters - -from hbba_lite.msg import Int32Stamped - -import hbba_lite - - -def callback(data1, data2): - rospy.loginfo('Data received : {} {}'.format(data1.data, data2.data)) - - -def main(): - rospy.init_node('test_on_off_hbba_approximate_time_synchronizer') - sub1 = message_filters.Subscriber('int_topic_1', Int32Stamped) - sub2 = message_filters.Subscriber('int_topic_2', Int32Stamped) - _ = hbba_lite.OnOffHbbaApproximateTimeSynchronizer([sub1, sub2], 10, 0.1, callback, 'int_topics/filter_state') - rospy.spin() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_on_off_hbba_publisher.py b/scripts/hbba_lite_python_tests/test_on_off_hbba_publisher.py deleted file mode 100755 index f25ff83..0000000 --- a/scripts/hbba_lite_python_tests/test_on_off_hbba_publisher.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -import rospy - -from std_msgs.msg import Int8 - -import hbba_lite - - -def main(): - rospy.init_node('test_on_off_hbba_publisher') - pub = hbba_lite.OnOffHbbaPublisher('int_topic', Int8, queue_size=10) - - rate = rospy.Rate(1) # 1hz - i = 0 - while not rospy.is_shutdown(): - pub.publish(Int8(i)) - i += 1 - rate.sleep() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_on_off_hbba_subscriber.py b/scripts/hbba_lite_python_tests/test_on_off_hbba_subscriber.py deleted file mode 100755 index 5f3d21c..0000000 --- a/scripts/hbba_lite_python_tests/test_on_off_hbba_subscriber.py +++ /dev/null @@ -1,21 +0,0 @@ -#!/usr/bin/env python3 -import rospy - -from std_msgs.msg import Int8 - -import hbba_lite - - -def callback(data): - rospy.loginfo('Data received : {}'.format(data.data)) - - -def main(): - rospy.init_node('test_on_off_hbba_subscriber') - sub = hbba_lite.OnOffHbbaSubscriber('int_topic', Int8, callback) - rospy.spin() - sub.unregister() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_on_off_hbba_time_synchronizer.py b/scripts/hbba_lite_python_tests/test_on_off_hbba_time_synchronizer.py deleted file mode 100755 index 1f0b886..0000000 --- a/scripts/hbba_lite_python_tests/test_on_off_hbba_time_synchronizer.py +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env python3 -import rospy -import message_filters - -from hbba_lite.msg import Int32Stamped - -import hbba_lite - - -def callback(data1, data2): - rospy.loginfo('Data received : {} {}'.format(data1.data, data2.data)) - - -def main(): - rospy.init_node('test_on_off_hbba_time_synchronizer') - sub1 = message_filters.Subscriber('int_topic_1', Int32Stamped) - sub2 = message_filters.Subscriber('int_topic_2', Int32Stamped) - _ = hbba_lite.OnOffHbbaTimeSynchronizer([sub1, sub2], 10, callback, 'int_topics/filter_state') - rospy.spin() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_throttling_hbba_approximate_time_synchronizer.py b/scripts/hbba_lite_python_tests/test_throttling_hbba_approximate_time_synchronizer.py deleted file mode 100755 index af80913..0000000 --- a/scripts/hbba_lite_python_tests/test_throttling_hbba_approximate_time_synchronizer.py +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env python3 -import rospy -import message_filters - -from hbba_lite.msg import Int32Stamped - -import hbba_lite - - -def callback(data1, data2): - rospy.loginfo('Data received : {} {}'.format(data1.data, data2.data)) - - -def main(): - rospy.init_node('test_throttling_hbba_approximate_time_synchronizer') - sub1 = message_filters.Subscriber('int_topic_1', Int32Stamped) - sub2 = message_filters.Subscriber('int_topic_2', Int32Stamped) - _ = hbba_lite.ThrottlingHbbaApproximateTimeSynchronizer([sub1, sub2], 10, 0.1, callback, 'int_topics/filter_state') - rospy.spin() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_throttling_hbba_publisher.py b/scripts/hbba_lite_python_tests/test_throttling_hbba_publisher.py deleted file mode 100755 index f1b553e..0000000 --- a/scripts/hbba_lite_python_tests/test_throttling_hbba_publisher.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -import rospy - -from std_msgs.msg import Int8 - -import hbba_lite - - -def main(): - rospy.init_node('test_throttling_hbba_publisher') - pub = hbba_lite.ThrottlingHbbaPublisher('int_topic', Int8, queue_size=10) - - rate = rospy.Rate(1) # 1hz - i = 0 - while not rospy.is_shutdown(): - pub.publish(Int8(i)) - i += 1 - rate.sleep() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_throttling_hbba_subscriber.py b/scripts/hbba_lite_python_tests/test_throttling_hbba_subscriber.py deleted file mode 100755 index 54e72de..0000000 --- a/scripts/hbba_lite_python_tests/test_throttling_hbba_subscriber.py +++ /dev/null @@ -1,21 +0,0 @@ -#!/usr/bin/env python3 -import rospy - -from std_msgs.msg import Int8 - -import hbba_lite - - -def callback(data): - rospy.loginfo('Data received : {}'.format(data.data)) - - -def main(): - rospy.init_node('test_throttling_hbba_subscriber') - sub = hbba_lite.ThrottlingHbbaSubscriber('int_topic', Int8, callback) - rospy.spin() - sub.unregister() - - -if __name__ == '__main__': - main() diff --git a/scripts/hbba_lite_python_tests/test_throttling_hbba_time_synchronizer.py b/scripts/hbba_lite_python_tests/test_throttling_hbba_time_synchronizer.py deleted file mode 100755 index 0cd7d3f..0000000 --- a/scripts/hbba_lite_python_tests/test_throttling_hbba_time_synchronizer.py +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env python3 -import rospy -import message_filters - -from hbba_lite.msg import Int32Stamped - -import hbba_lite - - -def callback(data1, data2): - rospy.loginfo('Data received : {} {}'.format(data1.data, data2.data)) - - -def main(): - rospy.init_node('test_throttling_hbba_time_synchronizer') - sub1 = message_filters.Subscriber('int_topic_1', Int32Stamped) - sub2 = message_filters.Subscriber('int_topic_2', Int32Stamped) - _ = hbba_lite.ThrottlingHbbaTimeSynchronizer([sub1, sub2], 10, callback, 'int_topics/filter_state') - rospy.spin() - - -if __name__ == '__main__': - main() diff --git a/setup.py b/setup.py deleted file mode 100644 index d96bbbc..0000000 --- a/setup.py +++ /dev/null @@ -1,12 +0,0 @@ -## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD - -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -# fetch values from package.xml -setup_args = generate_distutils_setup( - packages=['hbba_lite'], - package_dir={'': 'src'}, -) - -setup(**setup_args) diff --git a/src/arbitration_node.cpp b/src/arbitration_node.cpp deleted file mode 100644 index f46f855..0000000 --- a/src/arbitration_node.cpp +++ /dev/null @@ -1,156 +0,0 @@ -#include -#include - -#include -#include - -using namespace std; - -struct Topic -{ - string name; - int priority; - ros::Duration timeout; -}; - -class ArbitrationNode -{ - ros::NodeHandle& m_nodeHandle; - vector m_subscribers; - ros::Publisher m_publisher; - bool m_hasAdvertised; - - vector m_topics; - bool m_latch; - - optional m_currentTopicIndex; - ros::Time m_lastMessageTime; - -public: - ArbitrationNode(ros::NodeHandle& nodeHandle, vector topics, bool latch) - : m_nodeHandle(nodeHandle), - m_hasAdvertised(false), - m_topics(move(topics)), - m_latch(latch), - m_lastMessageTime(ros::Time::now()) - { - for (size_t i = 0; i < m_topics.size(); i++) - { - m_subscribers.emplace_back(m_nodeHandle.subscribe( - m_topics[i].name, - 1, - [this, i](const ros::MessageEvent& msgEvent) { callback(i, msgEvent); })); - } - } - - void run() { ros::spin(); } - -private: - void callback(size_t i, const ros::MessageEvent& msgEvent) - { - auto& msg = msgEvent.getConstMessage(); - if (!m_hasAdvertised) - { - advertise(msg); - } - - if (m_currentTopicIndex == nullopt || m_topics[i].priority <= m_topics[*m_currentTopicIndex].priority || - (ros::Time::now() - m_lastMessageTime) > m_topics[*m_currentTopicIndex].timeout) - { - m_currentTopicIndex = i; - m_lastMessageTime = ros::Time::now(); - m_publisher.publish(msg); - } - } - - void advertise(const boost::shared_ptr& msg) - { - m_publisher = msg->advertise(m_nodeHandle, "out", 10, m_latch); - m_hasAdvertised = true; - } -}; - - -bool getTopics(ros::NodeHandle& privateNodeHandle, vector& topics) -{ - vector value; - - XmlRpc::XmlRpcValue xmlTopics; - privateNodeHandle.getParam("topics", xmlTopics); - if (xmlTopics.getType() != XmlRpc::XmlRpcValue::TypeArray) - { - ROS_ERROR("Invalid topics format"); - return false; - } - - for (size_t i = 0; i < xmlTopics.size(); i++) - { - if (xmlTopics[i].getType() != XmlRpc::XmlRpcValue::TypeStruct || - xmlTopics[i]["name"].getType() != XmlRpc::XmlRpcValue::TypeString || - xmlTopics[i]["priority"].getType() != XmlRpc::XmlRpcValue::TypeInt || - xmlTopics[i]["timeout_s"].getType() != XmlRpc::XmlRpcValue::TypeDouble) - { - ROS_ERROR_STREAM( - "Invalid topics[" - << i << "]: name must be a string, priority must be a int and timeout_s must be a double."); - return false; - } - - topics.emplace_back(Topic{ - static_cast(xmlTopics[i]["name"]), - static_cast(xmlTopics[i]["priority"]), - ros::Duration(static_cast(xmlTopics[i]["timeout_s"]))}); - } - - return topics.size() > 0; -} - -bool hasUniquePriority(const vector& topics) -{ - unordered_set priorities; - - for (auto& topic : topics) - { - if (priorities.count(topic.priority) > 0) - { - return false; - } - - priorities.insert(topic.priority); - } - - return true; -} - - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "arbitration_node"); - - ros::NodeHandle nodeHandle; - ros::NodeHandle privateNodeHandle("~"); - - vector topics; - if (!getTopics(privateNodeHandle, topics)) - { - ROS_ERROR("The parameter topics must be set, not empty and valid."); - return -1; - } - if (!hasUniquePriority(topics)) - { - ROS_ERROR("The topic priorities must be unique."); - return -1; - } - - bool latch; - if (!privateNodeHandle.getParam("latch", latch)) - { - ROS_ERROR("The parameter latch is required."); - return -1; - } - - ArbitrationNode node(nodeHandle, topics, latch); - node.run(); - - return 0; -} diff --git a/src/hbba_lite_cpp/core/RosFilterPool.cpp b/src/hbba_lite_cpp/core/RosFilterPool.cpp deleted file mode 100644 index b6a7803..0000000 --- a/src/hbba_lite_cpp/core/RosFilterPool.cpp +++ /dev/null @@ -1,121 +0,0 @@ -#include -#include - -#include -#include - -using namespace std; - -RosFilterPool::RosFilterPool(ros::NodeHandle& nodeHandle, bool waitForService) - : m_nodeHandle(nodeHandle), - m_waitForService(waitForService) -{ -} - -void RosFilterPool::add(const string& name, FilterType type) -{ - lock_guard lock(m_mutex); - FilterPool::add(name, type); - - switch (type) - { - case FilterType::ON_OFF: - m_serviceClientsByName[name] = m_nodeHandle.serviceClient(name, true); - break; - - case FilterType::THROTTLING: - m_serviceClientsByName[name] = m_nodeHandle.serviceClient(name, true); - break; - - default: - throw HbbaLiteException("Not supported filter type"); - } -} - -void RosFilterPool::applyEnabling(const string& name, const FilterConfiguration& configuration) -{ - switch (m_typesByName[name]) - { - case FilterType::ON_OFF: - { - hbba_lite::SetOnOffFilterState srv; - srv.request.is_filtering_all_messages = false; - call(name, srv); - } - break; - - case FilterType::THROTTLING: - { - hbba_lite::SetThrottlingFilterState srv; - srv.request.is_filtering_all_messages = false; - srv.request.rate = configuration.rate(); - call(name, srv); - } - break; - - default: - throw HbbaLiteException("Not supported filter type"); - } -} - -void RosFilterPool::applyDisabling(const string& name) -{ - switch (m_typesByName[name]) - { - case FilterType::ON_OFF: - { - hbba_lite::SetOnOffFilterState srv; - srv.request.is_filtering_all_messages = true; - call(name, srv); - } - break; - - case FilterType::THROTTLING: - { - hbba_lite::SetThrottlingFilterState srv; - srv.request.is_filtering_all_messages = true; - srv.request.rate = 1; - call(name, srv); - } - break; - - default: - throw HbbaLiteException("Not supported filter type"); - } -} - -RosLogFilterPoolDecorator::RosLogFilterPoolDecorator(unique_ptr filterPool) : m_filterPool(move(filterPool)) -{ -} - -void RosLogFilterPoolDecorator::add(const std::string& name, FilterType type) -{ - lock_guard lock(m_mutex); - FilterPool::add(name, type); - m_filterPool->add(name, type); -} - -void RosLogFilterPoolDecorator::applyEnabling(const std::string& name, const FilterConfiguration& configuration) -{ - callApplyEnabling(*m_filterPool, name, configuration); - - switch (configuration.type()) - { - case FilterType::ON_OFF: - ROS_INFO_STREAM("HBBA filter state changed: " << name << " -> enabled"); - break; - - case FilterType::THROTTLING: - ROS_INFO_STREAM("HBBA filter state changed: " << name << " -> enabled (" << configuration.rate() << ")"); - break; - - default: - throw HbbaLiteException("Not supported filter type"); - } -} - -void RosLogFilterPoolDecorator::applyDisabling(const std::string& name) -{ - callApplyDisabling(*m_filterPool, name); - ROS_INFO_STREAM("HBBA filter state changed: " << name << " -> disabled"); -} diff --git a/src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp b/src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp deleted file mode 100644 index b2625fe..0000000 --- a/src/hbba_lite_cpp/core/RosStrategyStateLogger.cpp +++ /dev/null @@ -1,27 +0,0 @@ -#include - -#include - -using namespace std; - -void RosLogStrategyStateLogger::log(DesireType desireType, StrategyType strategyType, bool enabled) -{ - ROS_INFO_STREAM( - "HBBA strategy state changed: " - << "( " << desireType.name() << ", " << strategyType.name() << ") -> " << (enabled ? "enabled" : "disabled")); -} - - -RosTopicStrategyStateLogger::RosTopicStrategyStateLogger(ros::NodeHandle& nodeHandle) : m_nodeHandle(nodeHandle) -{ - m_strategyStatePub = m_nodeHandle.advertise("hbba_strategy_state_log", 1000); -} - -void RosTopicStrategyStateLogger::log(DesireType desireType, StrategyType strategyType, bool enabled) -{ - hbba_lite::StrategyState msg; - msg.desire_type_name = desireType.name(); - msg.strategy_type_name = strategyType.name(); - msg.enabled = enabled; - m_strategyStatePub.publish(msg); -} diff --git a/src/hbba_lite_cpp/filters/FilterState.cpp b/src/hbba_lite_cpp/filters/FilterState.cpp deleted file mode 100644 index 3b7ca96..0000000 --- a/src/hbba_lite_cpp/filters/FilterState.cpp +++ /dev/null @@ -1,68 +0,0 @@ -#include - -using namespace std; - -OnOffHbbaFilterState::OnOffHbbaFilterState(ros::NodeHandle& nodeHandle, const string& stateServiceName) - : m_isFilteringAllMessages(true) -{ - m_stateService = nodeHandle.advertiseService(stateServiceName, &OnOffHbbaFilterState::stateServiceCallback, this); -} - -bool OnOffHbbaFilterState::check() -{ - return !m_isFilteringAllMessages; -} - -bool OnOffHbbaFilterState::stateServiceCallback( - hbba_lite::SetOnOffFilterState::Request& request, - hbba_lite::SetOnOffFilterState::Response& response) -{ - m_isFilteringAllMessages = request.is_filtering_all_messages; - response.ok = true; - return true; -} - -ThrottlingHbbaFilterState::ThrottlingHbbaFilterState(ros::NodeHandle& nodeHandle, const string& stateServiceName) - : m_isFilteringAllMessages(true), - m_rate(1), - m_counter(0) -{ - m_stateService = - nodeHandle.advertiseService(stateServiceName, &ThrottlingHbbaFilterState::stateServiceCallback, this); -} - -bool ThrottlingHbbaFilterState::check() -{ - if (m_isFilteringAllMessages) - { - return false; - } - - bool isReady = false; - if (m_counter == 0) - { - isReady = true; - } - m_counter = (m_counter + 1) % m_rate; - return isReady; -} - -bool ThrottlingHbbaFilterState::stateServiceCallback( - hbba_lite::SetThrottlingFilterState::Request& request, - hbba_lite::SetThrottlingFilterState::Response& response) -{ - if (request.rate <= 0) - { - response.ok = false; - } - else - { - m_isFilteringAllMessages = request.is_filtering_all_messages; - m_rate = request.rate; - m_counter = 0; - - response.ok = true; - } - - return true; -} diff --git a/src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp b/src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp deleted file mode 100644 index 1118674..0000000 --- a/src/hbba_lite_cpp_tests/test_on_off_hbba_publisher.cpp +++ /dev/null @@ -1,25 +0,0 @@ -#include -#include - -#include - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "test_on_off_hbba_publisher"); - ros::NodeHandle nodeHandle; - - OnOffHbbaPublisher pub(nodeHandle, "int_topic", 10); - - ros::Rate rate(1); - for (int i = 0; ros::ok(); i++) - { - std_msgs::Int8 msg; - msg.data = i; - pub.publish(msg); - - ros::spinOnce(); - rate.sleep(); - } - - return 0; -} diff --git a/src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp b/src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp deleted file mode 100644 index 23c10f2..0000000 --- a/src/hbba_lite_cpp_tests/test_on_off_hbba_subscriber.cpp +++ /dev/null @@ -1,20 +0,0 @@ -#include -#include - -#include - -void callback(const std_msgs::Int8::ConstPtr& msg) -{ - ROS_INFO("Data received : %i", static_cast(msg->data)); -} - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "test_on_off_hbba_subscriber"); - ros::NodeHandle nodeHandle; - - OnOffHbbaSubscriber sub(nodeHandle, "int_topic", 10, &callback); - ros::spin(); - - return 0; -} diff --git a/src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp b/src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp deleted file mode 100644 index be2ad0f..0000000 --- a/src/hbba_lite_cpp_tests/test_throttling_hbba_publisher.cpp +++ /dev/null @@ -1,25 +0,0 @@ -#include -#include - -#include - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "test_on_off_hbba_publisher"); - ros::NodeHandle nodeHandle; - - ThrottlingHbbaPublisher pub(nodeHandle, "int_topic", 10); - - ros::Rate rate(1); - for (int i = 0; ros::ok(); i++) - { - std_msgs::Int8 msg; - msg.data = i; - pub.publish(msg); - - ros::spinOnce(); - rate.sleep(); - } - - return 0; -} diff --git a/src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp b/src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp deleted file mode 100644 index 202bf44..0000000 --- a/src/hbba_lite_cpp_tests/test_throttling_hbba_subscriber.cpp +++ /dev/null @@ -1,20 +0,0 @@ -#include -#include - -#include - -void callback(const std_msgs::Int8::ConstPtr& msg) -{ - ROS_INFO("Data received : %i", static_cast(msg->data)); -} - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "test_on_off_hbba_subscriber"); - ros::NodeHandle nodeHandle; - - ThrottlingHbbaSubscriber sub(nodeHandle, "int_topic", 10, &callback); - ros::spin(); - - return 0; -} diff --git a/src/on_off_hbba_filter_node.cpp b/src/on_off_hbba_filter_node.cpp deleted file mode 100644 index 9ba9997..0000000 --- a/src/on_off_hbba_filter_node.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#include -#include - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "on_off_hbba_filter_node"); - ros::NodeHandle nodeHandle; - - OnOffHbbaFilterNode onOffHbbaFilterNode(nodeHandle); - onOffHbbaFilterNode.run(); - - return 0; -} diff --git a/src/throttling_hbba_filter_node.cpp b/src/throttling_hbba_filter_node.cpp deleted file mode 100644 index aa7de9a..0000000 --- a/src/throttling_hbba_filter_node.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#include -#include - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "throttling_hbba_filter_node"); - ros::NodeHandle nodeHandle; - - ThrottlingHbbaFilterNode throttlingHbbaFilterNode(nodeHandle); - throttlingHbbaFilterNode.run(); - - return 0; -}