Skip to content

Commit

Permalink
remove line break and add static executor in cmakelist
Browse files Browse the repository at this point in the history
  • Loading branch information
peterpena committed Jul 20, 2020
1 parent d297dc5 commit 4d13604
Show file tree
Hide file tree
Showing 6 changed files with 7 additions and 12 deletions.
4 changes: 2 additions & 2 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/expand_topic_or_service_name.cpp
src/rclcpp/executors/multi_threaded_executor.cpp
src/rclcpp/executors/single_threaded_executor.cpp
# src/rclcpp/executors/static_executor_entities_collector.cpp
# src/rclcpp/executors/static_single_threaded_executor.cpp
src/rclcpp/executors/static_executor_entities_collector.cpp
src/rclcpp/executors/static_single_threaded_executor.cpp
src/rclcpp/future_return_code.cpp
src/rclcpp/graph_listener.cpp
src/rclcpp/guard_condition.cpp
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,7 @@ class CallbackGroup
RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup)

RCLCPP_PUBLIC
explicit CallbackGroup(
CallbackGroupType group_type);
explicit CallbackGroup(CallbackGroupType group_type);

template<typename Function>
rclcpp::SubscriptionBase::SharedPtr
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,7 @@ class Node : public std::enable_shared_from_this<Node>
/// Create and return a callback group.
RCLCPP_PUBLIC
rclcpp::CallbackGroup::SharedPtr
create_callback_group(
rclcpp::CallbackGroupType group_type);
create_callback_group(rclcpp::CallbackGroupType group_type);

/// Return the list of callback groups in the node.
RCLCPP_PUBLIC
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,7 @@ class NodeBaseInterface
RCLCPP_PUBLIC
virtual
rclcpp::CallbackGroup::SharedPtr
create_callback_group(
rclcpp::CallbackGroupType group_type) = 0;
create_callback_group(rclcpp::CallbackGroupType group_type) = 0;

/// Return the default callback group.
RCLCPP_PUBLIC
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -211,8 +211,7 @@ Node::get_logger() const
}

rclcpp::CallbackGroup::SharedPtr
Node::create_callback_group(
rclcpp::CallbackGroupType group_type)
Node::create_callback_group(rclcpp::CallbackGroupType group_type)
{
return node_base_->create_callback_group(group_type);
}
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,8 +216,7 @@ NodeBase::get_shared_rcl_node_handle() const
}

rclcpp::CallbackGroup::SharedPtr
NodeBase::create_callback_group(
rclcpp::CallbackGroupType group_type)
NodeBase::create_callback_group(rclcpp::CallbackGroupType group_type)
{
using rclcpp::CallbackGroup;
using rclcpp::CallbackGroupType;
Expand Down

0 comments on commit 4d13604

Please sign in to comment.