Skip to content

Commit

Permalink
Refactor ROS 2 node as a component (#63)
Browse files Browse the repository at this point in the history
**Public-Facing Changes**
Refactor ROS 2 node as a component


**Description**
Allows to run the ROS2 version both as standalone node or as a
component.

For the standalone version we simply create a `ComponentManager` and
load the foxglove bridge component. I'm not sure if this is best
practice, but it has the advantage that it does not additional header
files to be included which would require an additional refactoring.


Fixes #28
  • Loading branch information
achim-k committed Nov 22, 2022
1 parent e9ae10d commit 6b2570d
Show file tree
Hide file tree
Showing 4 changed files with 71 additions and 35 deletions.
22 changes: 18 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -111,13 +111,27 @@ elseif("$ENV{ROS_VERSION}" STREQUAL "2")

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)

add_executable(foxglove_bridge
add_library(foxglove_bridge_component SHARED
ros2_foxglove_bridge/src/message_definition_cache.cpp
ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
)
target_include_directories(foxglove_bridge_component
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/foxglove_bridge_base/include>
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/ros2_foxglove_bridge/include>
$<INSTALL_INTERFACE:include>
)
ament_target_dependencies(foxglove_bridge_component rclcpp rclcpp_components)
target_link_libraries(foxglove_bridge_component foxglove_bridge_base)
rclcpp_components_register_nodes(foxglove_bridge_component "foxglove_bridge::FoxgloveBridge")

add_executable(foxglove_bridge
ros2_foxglove_bridge/src/ros2_foxglove_bridge_node.cpp
)
target_include_directories(foxglove_bridge SYSTEM PRIVATE ${rclcpp_INCLUDE_DIRS})
target_link_libraries(foxglove_bridge foxglove_bridge_base ${rclcpp_LIBRARIES})
ament_target_dependencies(foxglove_bridge rclcpp rclcpp_components)
else()
message(FATAL_ERROR "Could not find ament_cmake")
endif()
Expand Down Expand Up @@ -177,11 +191,11 @@ elseif(ROS_BUILD_TYPE STREQUAL "ament_cmake")
install(TARGETS foxglove_bridge
DESTINATION lib/${PROJECT_NAME}
)
install(TARGETS foxglove_bridge_base
install(TARGETS foxglove_bridge_base foxglove_bridge_component
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
ament_export_libraries(foxglove_bridge_base)
ament_export_libraries(foxglove_bridge_base foxglove_bridge_component)
ament_package()
endif()
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<!-- ROS 2 runtime dependencies -->
<depend condition="$ROS_VERSION == 2">ament_index_cpp</depend>
<depend condition="$ROS_VERSION == 2">rclcpp</depend>
<depend condition="$ROS_VERSION == 2">rclcpp_components</depend>

<!-- Test dependencies -->
<build_depend condition="$ROS_VERSION == 1">rostest</build_depend>
Expand Down
41 changes: 10 additions & 31 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@

constexpr uint16_t DEFAULT_PORT = 8765;
constexpr char DEFAULT_ADDRESS[] = "0.0.0.0";
constexpr int DEFAULT_NUM_THREADS = 0;
constexpr size_t DEFAULT_MAX_QOS_DEPTH = 10;

using namespace std::chrono_literals;
Expand All @@ -24,6 +23,8 @@ using LogLevel = foxglove::WebSocketLogLevel;
using Subscription = std::pair<rclcpp::GenericSubscription::SharedPtr, rclcpp::SubscriptionOptions>;
using SubscriptionsByClient = std::map<foxglove::ConnHandle, Subscription, std::owner_less<>>;

namespace foxglove_bridge {

class FoxgloveBridge : public rclcpp::Node {
public:
using TopicAndDatatype = std::pair<std::string, std::string>;
Expand Down Expand Up @@ -74,19 +75,6 @@ class FoxgloveBridge : public rclcpp::Node {
keyfileDescription.read_only = true;
this->declare_parameter("keyfile", "", keyfileDescription);

auto numThreadsDescription = rcl_interfaces::msg::ParameterDescriptor{};
numThreadsDescription.name = "num_threads";
numThreadsDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
numThreadsDescription.description =
"The number of threads to use for the ROS node executor. 0 means one thread per CPU core.";
numThreadsDescription.read_only = true;
numThreadsDescription.additional_constraints = "Must be a non-negative integer";
numThreadsDescription.integer_range.resize(1);
numThreadsDescription.integer_range[0].from_value = 0;
numThreadsDescription.integer_range[0].to_value = INT32_MAX;
numThreadsDescription.integer_range[0].step = 1;
this->declare_parameter("num_threads", DEFAULT_NUM_THREADS, numThreadsDescription);

auto maxQosDepthDescription = rcl_interfaces::msg::ParameterDescriptor{};
maxQosDepthDescription.name = "max_qos_depth";
maxQosDepthDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
Expand Down Expand Up @@ -143,13 +131,6 @@ class FoxgloveBridge : public rclcpp::Node {
RCLCPP_INFO(this->get_logger(), "Shutdown complete");
}

size_t numThreads() {
int numThreads;
rclcpp::spin_some(this->get_node_base_interface());
this->get_parameter_or("num_threads", numThreads, DEFAULT_NUM_THREADS);
return size_t(numThreads);
}

void rosgraphPollThread() {
updateAdvertisedTopics();

Expand Down Expand Up @@ -504,13 +485,11 @@ class FoxgloveBridge : public rclcpp::Node {
}
};

int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
auto bridgeNode = std::make_shared<FoxgloveBridge>();
rclcpp::executors::MultiThreadedExecutor executor{rclcpp::ExecutorOptions{},
bridgeNode->numThreads()};
executor.add_node(bridgeNode);
executor.spin();
rclcpp::shutdown();
return 0;
}
} // namespace foxglove_bridge

#include <rclcpp_components/register_node_macro.hpp>

// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(foxglove_bridge::FoxgloveBridge)
42 changes: 42 additions & 0 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
#include <rclcpp_components/component_manager.hpp>

int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);

auto dummyNode = std::make_shared<rclcpp::Node>("dummy");
auto numThreadsDescription = rcl_interfaces::msg::ParameterDescriptor{};
numThreadsDescription.name = "num_threads";
numThreadsDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
numThreadsDescription.description =
"The number of threads to use for the ROS node executor. 0 means one thread per CPU core.";
numThreadsDescription.read_only = true;
numThreadsDescription.additional_constraints = "Must be a non-negative integer";
numThreadsDescription.integer_range.resize(1);
numThreadsDescription.integer_range[0].from_value = 0;
numThreadsDescription.integer_range[0].to_value = INT32_MAX;
numThreadsDescription.integer_range[0].step = 1;
constexpr int DEFAULT_NUM_THREADS = 0;
dummyNode->declare_parameter("num_threads", DEFAULT_NUM_THREADS, numThreadsDescription);

const auto numThreads = dummyNode->get_parameter("num_threads").as_int();

auto executor =
rclcpp::executors::MultiThreadedExecutor::make_shared(rclcpp::ExecutorOptions{}, numThreads);

rclcpp_components::ComponentManager componentManager(executor, "ComponentManager");
const auto componentResources = componentManager.get_component_resources("foxglove_bridge");
RCLCPP_INFO(componentManager.get_logger(), std::to_string(numThreads).c_str());

if (componentResources.empty()) {
RCLCPP_INFO(componentManager.get_logger(), "No loadable resources found");
return EXIT_FAILURE;
}

auto componentFactory = componentManager.create_component_factory(componentResources.front());
auto node = componentFactory->create_node_instance(rclcpp::NodeOptions());

executor->spin();
rclcpp::shutdown();

return EXIT_SUCCESS;
}

0 comments on commit 6b2570d

Please sign in to comment.