diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..80f4f71 --- /dev/null +++ b/.clang-format @@ -0,0 +1,68 @@ +--- +BasedOnStyle: Google +AccessModifierOffset: -2 +ConstructorInitializerIndentWidth: 2 +AlignEscapedNewlinesLeft: false +AlignTrailingComments: true +AllowAllParametersOfDeclarationOnNextLine: false +AllowShortIfStatementsOnASingleLine: false +AllowShortLoopsOnASingleLine: false +AllowShortFunctionsOnASingleLine: None +AlwaysBreakTemplateDeclarations: true +AlwaysBreakBeforeMultilineStrings: false +BreakBeforeBinaryOperators: false +BreakBeforeTernaryOperators: false +BreakConstructorInitializers: BeforeComma +BinPackParameters: true +ColumnLimit: 90 +ConstructorInitializerAllOnOneLineOrOnePerLine: true +DerivePointerBinding: false +PointerBindsToType: true +ExperimentalAutoDetectBinPacking: false +IndentCaseLabels: true +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCSpaceBeforeProtocolList: true +PenaltyBreakBeforeFirstCallParameter: 19 +PenaltyBreakComment: 60 +PenaltyBreakString: 1 +PenaltyBreakFirstLessLess: 1000 +PenaltyExcessCharacter: 1000 +PenaltyReturnTypeOnItsOwnLine: 90 +SpacesBeforeTrailingComments: 2 +Cpp11BracedListStyle: false +Standard: Auto +IndentWidth: 2 +TabWidth: 2 +UseTab: Never +IndentFunctionDeclarationAfterType: false +SpacesInParentheses: false +SpacesInAngles: false +SpaceInEmptyParentheses: false +SpacesInCStyleCastParentheses: false +SpaceAfterControlStatementKeyword: true +SpaceBeforeAssignmentOperators: true +SpaceBeforeParens: Never +ContinuationIndentWidth: 4 +SortIncludes: false +SpaceAfterCStyleCast: false +ReflowComments: false + +# Configure each individual brace in BraceWrapping +BreakBeforeBraces: Custom + +# Control of individual brace wrapping cases +BraceWrapping: { + AfterClass: 'true', + AfterControlStatement: 'true', + AfterEnum : 'true', + AfterFunction : 'true', + AfterNamespace : 'true', + AfterStruct : 'true', + AfterUnion : 'true', + BeforeCatch : 'true', + BeforeElse : 'true', + IndentBraces : 'false', + SplitEmptyFunction: 'false' +} +... diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml new file mode 100644 index 0000000..6095e08 --- /dev/null +++ b/.github/workflows/pre-commit.yaml @@ -0,0 +1,14 @@ +name: pre-commit + +on: + pull_request: + push: + branches: [master] + +jobs: + pre-commit: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v3 + - uses: actions/setup-python@v3 + - uses: pre-commit/action@v3.0.1 diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 0000000..e6ace82 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,44 @@ + +# To use: +# +# pre-commit run -a +# +# Or: +# +# pre-commit install # (runs every time you commit in git) +# +# To update this file: +# +# pre-commit autoupdate +# +# See https://github.com/pre-commit/pre-commit + +exclude: ^3rdparty/|3rdparty|^include/behaviortree_cpp/contrib/ +repos: + + # Standard hooks + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.5.0 + hooks: + - id: check-added-large-files + - id: check-ast + - id: check-case-conflict + - id: check-docstring-first + - id: check-merge-conflict + - id: check-symlinks + - id: check-xml + - id: check-yaml + - id: debug-statements + - id: end-of-file-fixer + exclude_types: [svg] + - id: mixed-line-ending + - id: trailing-whitespace + exclude_types: [svg] + - id: fix-byte-order-marker + + # CPP hooks + - repo: https://github.com/pre-commit/mirrors-clang-format + rev: v17.0.6 + hooks: + - id: clang-format + args: ['-fallback-style=none', '-i'] diff --git a/LICENSE b/LICENSE index 7fc7319..5f09852 100644 --- a/LICENSE +++ b/LICENSE @@ -202,4 +202,3 @@ distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. - diff --git a/README.md b/README.md index 32c343b..ce5b332 100644 --- a/README.md +++ b/README.md @@ -29,5 +29,3 @@ wrap your Nodes into plugins that can be loaded at run-time. A lot of code is either inspired or copied from [Nav2](https://navigation.ros.org/). For this reason, we retain the same license and copyright. - - diff --git a/behaviortree_ros2/CMakeLists.txt b/behaviortree_ros2/CMakeLists.txt index 3c46da2..01378ff 100644 --- a/behaviortree_ros2/CMakeLists.txt +++ b/behaviortree_ros2/CMakeLists.txt @@ -26,8 +26,8 @@ ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_DEPS}) ###################################################### # INSTALL -install(DIRECTORY include/ DESTINATION include/) - +install(DIRECTORY include/ DESTINATION include/) + ament_export_include_directories(include) ament_export_dependencies(${THIS_PACKAGE_DEPS}) diff --git a/behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp b/behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp index e125afc..7bb2f99 100644 --- a/behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp +++ b/behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp @@ -40,14 +40,20 @@ enum ActionNodeErrorCode inline const char* toStr(const ActionNodeErrorCode& err) { - switch (err) + switch(err) { - case SERVER_UNREACHABLE: return "SERVER_UNREACHABLE"; - case SEND_GOAL_TIMEOUT: return "SEND_GOAL_TIMEOUT"; - case GOAL_REJECTED_BY_SERVER: return "GOAL_REJECTED_BY_SERVER"; - case ACTION_ABORTED: return "ACTION_ABORTED"; - case ACTION_CANCELLED: return "ACTION_CANCELLED"; - case INVALID_GOAL: return "INVALID_GOAL"; + case SERVER_UNREACHABLE: + return "SERVER_UNREACHABLE"; + case SEND_GOAL_TIMEOUT: + return "SEND_GOAL_TIMEOUT"; + case GOAL_REJECTED_BY_SERVER: + return "GOAL_REJECTED_BY_SERVER"; + case ACTION_ABORTED: + return "ACTION_ABORTED"; + case ACTION_CANCELLED: + return "ACTION_CANCELLED"; + case INVALID_GOAL: + return "INVALID_GOAL"; } return nullptr; } @@ -70,10 +76,9 @@ inline const char* toStr(const ActionNodeErrorCode& err) * 1. If a value is passes in the InputPort "action_name", use that * 2. Otherwise, use the value in RosNodeParams::default_port_value */ -template +template class RosActionNode : public BT::ActionNodeBase { - public: // Type definitions using ActionType = ActionT; @@ -89,8 +94,7 @@ class RosActionNode : public BT::ActionNodeBase * factory.registerNodeType<>(node_name, params); * */ - explicit RosActionNode(const std::string & instance_name, - const BT::NodeConfig& conf, + explicit RosActionNode(const std::string& instance_name, const BT::NodeConfig& conf, const RosNodeParams& params); virtual ~RosActionNode() = default; @@ -104,9 +108,8 @@ class RosActionNode : public BT::ActionNodeBase */ static PortsList providedBasicPorts(PortsList addition) { - PortsList basic = { - InputPort("action_name", "__default__placeholder__", "Action server name") - }; + PortsList basic = { InputPort("action_name", "__default__placeholder__", + "Action server name") }; basic.insert(addition.begin(), addition.end()); return basic; } @@ -122,7 +125,8 @@ class RosActionNode : public BT::ActionNodeBase /// @brief Callback executed when the node is halted. Note that cancelGoal() /// is done automatically. - virtual void onHalt() {} + virtual void onHalt() + {} /** setGoal s a callback that allows the user to set * the goal message (ActionT::Goal). @@ -159,14 +163,12 @@ class RosActionNode : public BT::ActionNodeBase /// Method used to send a request to the Action server to cancel the current goal void cancelGoal(); - /// The default halt() implementation will call cancelGoal if necessary. void halt() override final; NodeStatus tick() override final; protected: - std::shared_ptr node_; std::string prev_action_name_; bool action_name_may_change_ = false; @@ -174,7 +176,6 @@ class RosActionNode : public BT::ActionNodeBase const std::chrono::milliseconds wait_for_server_timeout_; private: - ActionClientPtr action_client_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; @@ -187,21 +188,21 @@ class RosActionNode : public BT::ActionNodeBase bool goal_received_; WrappedResult result_; - bool createClient(const std::string &action_name); + bool createClient(const std::string& action_name); }; //---------------------------------------------------------------- //---------------------- DEFINITIONS ----------------------------- //---------------------------------------------------------------- -template inline - RosActionNode::RosActionNode(const std::string & instance_name, - const NodeConfig &conf, - const RosNodeParams ¶ms): - BT::ActionNodeBase(instance_name, conf), - node_(params.nh), - server_timeout_(params.server_timeout), - wait_for_server_timeout_(params.wait_for_server_timeout) +template +inline RosActionNode::RosActionNode(const std::string& instance_name, + const NodeConfig& conf, + const RosNodeParams& params) + : BT::ActionNodeBase(instance_name, conf) + , node_(params.nh) + , server_timeout_(params.server_timeout) + , wait_for_server_timeout_(params.wait_for_server_timeout) { // Three cases: // - we use the default action_name in RosNodeParams when port is empty @@ -216,11 +217,13 @@ template inline if(bb_action_name.empty() || bb_action_name == "__default__placeholder__") { - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [action_name] in the InputPort and the RosNodeParams are empty."); + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [action_name] in the InputPort and the " + "RosNodeParams are empty."); } - else { + else + { createClient(params.default_port_value); } } @@ -231,33 +234,38 @@ template inline // create the client in the constructor. createClient(bb_action_name); } - else { + else + { action_name_may_change_ = true; // createClient will be invoked in the first tick(). } } - else { - - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [action_name] in the InputPort and the RosNodeParams are empty."); + else + { + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [action_name] in the InputPort and the RosNodeParams " + "are empty."); } - else { + else + { createClient(params.default_port_value); } } } -template inline - bool RosActionNode::createClient(const std::string& action_name) +template +inline bool RosActionNode::createClient(const std::string& action_name) { if(action_name.empty()) { throw RuntimeError("action_name is empty"); } - callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); + callback_group_ = + node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + callback_group_executor_.add_callback_group(callback_group_, + node_->get_node_base_interface()); action_client_ = rclcpp_action::create_client(node_, action_name, callback_group_); prev_action_name_ = action_name; @@ -265,14 +273,15 @@ template inline bool found = action_client_->wait_for_action_server(wait_for_server_timeout_); if(!found) { - RCLCPP_ERROR(node_->get_logger(), "%s: Action server with name '%s' is not reachable.", - name().c_str(), prev_action_name_.c_str()); + RCLCPP_ERROR(node_->get_logger(), + "%s: Action server with name '%s' is not reachable.", name().c_str(), + prev_action_name_.c_str()); } return found; } -template inline - NodeStatus RosActionNode::tick() +template +inline NodeStatus RosActionNode::tick() { // First, check if the action_client_ is valid and that the name of the // action_name in the port didn't change. @@ -288,17 +297,17 @@ template inline } //------------------------------------------ - auto CheckStatus = [](NodeStatus status) - { - if( !isStatusCompleted(status) ) + auto CheckStatus = [](NodeStatus status) { + if(!isStatusCompleted(status)) { - throw std::logic_error("RosActionNode: the callback must return either SUCCESS of FAILURE"); + throw std::logic_error("RosActionNode: the callback must return either SUCCESS of " + "FAILURE"); } return status; }; // first step to be done only at the beginning of the Action - if (status() == BT::NodeStatus::IDLE) + if(status() == BT::NodeStatus::IDLE) { setStatus(NodeStatus::RUNNING); @@ -309,77 +318,80 @@ template inline Goal goal; - if( !setGoal(goal) ) + if(!setGoal(goal)) { - return CheckStatus( onFailure(INVALID_GOAL) ); + return CheckStatus(onFailure(INVALID_GOAL)); } typename ActionClient::SendGoalOptions goal_options; //-------------------- goal_options.feedback_callback = - [this](typename GoalHandle::SharedPtr, - const std::shared_ptr feedback) - { - on_feedback_state_change_ = onFeedback(feedback); - if( on_feedback_state_change_ == NodeStatus::IDLE) - { - throw std::logic_error("onFeedback must not return IDLE"); - } - emitWakeUpSignal(); - }; + [this](typename GoalHandle::SharedPtr, + const std::shared_ptr feedback) { + on_feedback_state_change_ = onFeedback(feedback); + if(on_feedback_state_change_ == NodeStatus::IDLE) + { + throw std::logic_error("onFeedback must not return IDLE"); + } + emitWakeUpSignal(); + }; //-------------------- - goal_options.result_callback = - [this](const WrappedResult& result) - { - if (goal_handle_->get_goal_id() == result.goal_id) { - RCLCPP_DEBUG( node_->get_logger(), "result_callback" ); + goal_options.result_callback = [this](const WrappedResult& result) { + if(goal_handle_->get_goal_id() == result.goal_id) + { + RCLCPP_DEBUG(node_->get_logger(), "result_callback"); result_ = result; emitWakeUpSignal(); } }; //-------------------- goal_options.goal_response_callback = - [this](typename GoalHandle::SharedPtr const future_handle) - { - auto goal_handle_ = future_handle.get(); - if (!goal_handle_) - { - RCLCPP_ERROR(node_->get_logger(), "Goal was rejected by server"); - } else { - RCLCPP_DEBUG(node_->get_logger(), "Goal accepted by server, waiting for result"); - } - }; + [this](typename GoalHandle::SharedPtr const future_handle) { + auto goal_handle_ = future_handle.get(); + if(!goal_handle_) + { + RCLCPP_ERROR(node_->get_logger(), "Goal was rejected by server"); + } + else + { + RCLCPP_DEBUG(node_->get_logger(), "Goal accepted by server, waiting for " + "result"); + } + }; //-------------------- // Check if server is ready if(!action_client_->action_server_is_ready()) return onFailure(SERVER_UNREACHABLE); - future_goal_handle_ = action_client_->async_send_goal( goal, goal_options ); + future_goal_handle_ = action_client_->async_send_goal(goal, goal_options); time_goal_sent_ = node_->now(); return NodeStatus::RUNNING; } - if (status() == NodeStatus::RUNNING) + if(status() == NodeStatus::RUNNING) { callback_group_executor_.spin_some(); // FIRST case: check if the goal request has a timeout - if( !goal_received_ ) + if(!goal_received_) { auto nodelay = std::chrono::milliseconds(0); - auto timeout = rclcpp::Duration::from_seconds( double(server_timeout_.count()) / 1000); + auto timeout = + rclcpp::Duration::from_seconds(double(server_timeout_.count()) / 1000); - auto ret = callback_group_executor_.spin_until_future_complete(future_goal_handle_, nodelay); - if (ret != rclcpp::FutureReturnCode::SUCCESS) + auto ret = callback_group_executor_.spin_until_future_complete(future_goal_handle_, + nodelay); + if(ret != rclcpp::FutureReturnCode::SUCCESS) { - if( (node_->now() - time_goal_sent_) > timeout ) + if((node_->now() - time_goal_sent_) > timeout) { - return CheckStatus( onFailure(SEND_GOAL_TIMEOUT) ); + return CheckStatus(onFailure(SEND_GOAL_TIMEOUT)); } - else{ + else + { return NodeStatus::RUNNING; } } @@ -389,39 +401,41 @@ template inline goal_handle_ = future_goal_handle_.get(); future_goal_handle_ = {}; - if (!goal_handle_) { - return CheckStatus( onFailure( GOAL_REJECTED_BY_SERVER ) ); + if(!goal_handle_) + { + return CheckStatus(onFailure(GOAL_REJECTED_BY_SERVER)); } } } // SECOND case: onFeedback requested a stop - if( on_feedback_state_change_ != NodeStatus::RUNNING ) + if(on_feedback_state_change_ != NodeStatus::RUNNING) { cancelGoal(); return on_feedback_state_change_; } // THIRD case: result received, requested a stop - if( result_.code != rclcpp_action::ResultCode::UNKNOWN) + if(result_.code != rclcpp_action::ResultCode::UNKNOWN) { - if( result_.code == rclcpp_action::ResultCode::ABORTED ) + if(result_.code == rclcpp_action::ResultCode::ABORTED) { - return CheckStatus( onFailure( ACTION_ABORTED ) ); + return CheckStatus(onFailure(ACTION_ABORTED)); } - else if( result_.code == rclcpp_action::ResultCode::CANCELED ) + else if(result_.code == rclcpp_action::ResultCode::CANCELED) { - return CheckStatus( onFailure( ACTION_CANCELLED ) ); + return CheckStatus(onFailure(ACTION_CANCELLED)); } - else{ - return CheckStatus( onResultReceived( result_ ) ); + else + { + return CheckStatus(onResultReceived(result_)); } } } return NodeStatus::RUNNING; } -template inline - void RosActionNode::halt() +template +inline void RosActionNode::halt() { if(status() == BT::NodeStatus::RUNNING) { @@ -430,35 +444,31 @@ template inline } } -template inline - void RosActionNode::cancelGoal() +template +inline void RosActionNode::cancelGoal() { - if (!goal_handle_) + if(!goal_handle_) { - RCLCPP_WARN( node_->get_logger(), "cancelGoal called on an empty goal_handle"); + RCLCPP_WARN(node_->get_logger(), "cancelGoal called on an empty goal_handle"); return; } auto future_result = action_client_->async_get_result(goal_handle_); auto future_cancel = action_client_->async_cancel_goal(goal_handle_); - if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) != - rclcpp::FutureReturnCode::SUCCESS) + if(callback_group_executor_.spin_until_future_complete( + future_cancel, server_timeout_) != rclcpp::FutureReturnCode::SUCCESS) { - RCLCPP_ERROR( node_->get_logger(), "Failed to cancel action server for [%s]", + RCLCPP_ERROR(node_->get_logger(), "Failed to cancel action server for [%s]", prev_action_name_.c_str()); } - if (callback_group_executor_.spin_until_future_complete(future_result, server_timeout_) != - rclcpp::FutureReturnCode::SUCCESS) + if(callback_group_executor_.spin_until_future_complete( + future_result, server_timeout_) != rclcpp::FutureReturnCode::SUCCESS) { - RCLCPP_ERROR( node_->get_logger(), "Failed to get result call failed :( for [%s]", + RCLCPP_ERROR(node_->get_logger(), "Failed to get result call failed :( for [%s]", prev_action_name_.c_str()); } } - - - } // namespace BT - diff --git a/behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp b/behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp index 67a6750..3ceae00 100644 --- a/behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp +++ b/behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp @@ -36,12 +36,16 @@ enum ServiceNodeErrorCode inline const char* toStr(const ServiceNodeErrorCode& err) { - switch (err) + switch(err) { - case SERVICE_UNREACHABLE: return "SERVICE_UNREACHABLE"; - case SERVICE_TIMEOUT: return "SERVICE_TIMEOUT"; - case INVALID_REQUEST: return "INVALID_REQUEST"; - case SERVICE_ABORTED: return "SERVICE_ABORTED"; + case SERVICE_UNREACHABLE: + return "SERVICE_UNREACHABLE"; + case SERVICE_TIMEOUT: + return "SERVICE_TIMEOUT"; + case INVALID_REQUEST: + return "INVALID_REQUEST"; + case SERVICE_ABORTED: + return "SERVICE_ABORTED"; } return nullptr; } @@ -64,10 +68,9 @@ inline const char* toStr(const ServiceNodeErrorCode& err) * 1. If a value is passes in the InputPort "service_name", use that * 2. Otherwise, use the value in RosNodeParams::default_port_value */ -template +template class RosServiceNode : public BT::ActionNodeBase { - public: // Type definitions using ServiceClient = typename rclcpp::Client; @@ -78,8 +81,7 @@ class RosServiceNode : public BT::ActionNodeBase * * factory.registerNodeType<>(node_name, params); */ - explicit RosServiceNode(const std::string & instance_name, - const BT::NodeConfig& conf, + explicit RosServiceNode(const std::string& instance_name, const BT::NodeConfig& conf, const BT::RosNodeParams& params); virtual ~RosServiceNode() = default; @@ -93,9 +95,8 @@ class RosServiceNode : public BT::ActionNodeBase */ static PortsList providedBasicPorts(PortsList addition) { - PortsList basic = { - InputPort("service_name", "__default__placeholder__", "Service name") - }; + PortsList basic = { InputPort("service_name", "__default__placeholder__", + "Service name") }; basic.insert(addition.begin(), addition.end()); return basic; } @@ -127,18 +128,18 @@ class RosServiceNode : public BT::ActionNodeBase /** Callback invoked when the response is received by the server. * It is up to the user to define if this returns SUCCESS or FAILURE. */ - virtual BT::NodeStatus onResponseReceived(const typename Response::SharedPtr& response) = 0; + virtual BT::NodeStatus + onResponseReceived(const typename Response::SharedPtr& response) = 0; /** Callback invoked when something goes wrong; you can override it. * It must return either SUCCESS or FAILURE. */ virtual BT::NodeStatus onFailure(ServiceNodeErrorCode /*error*/) - { + { return NodeStatus::FAILURE; } protected: - std::shared_ptr node_; std::string prev_service_name_; bool service_name_may_change_ = false; @@ -146,7 +147,6 @@ class RosServiceNode : public BT::ActionNodeBase const std::chrono::milliseconds wait_for_service_timeout_; private: - typename std::shared_ptr service_client_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; @@ -158,21 +158,21 @@ class RosServiceNode : public BT::ActionNodeBase bool response_received_; typename Response::SharedPtr response_; - bool createClient(const std::string &service_name); + bool createClient(const std::string& service_name); }; //---------------------------------------------------------------- //---------------------- DEFINITIONS ----------------------------- //---------------------------------------------------------------- -template inline - RosServiceNode::RosServiceNode(const std::string & instance_name, - const NodeConfig &conf, - const RosNodeParams& params): - BT::ActionNodeBase(instance_name, conf), - node_(params.nh), - service_timeout_(params.server_timeout), - wait_for_service_timeout_(params.wait_for_server_timeout) +template +inline RosServiceNode::RosServiceNode(const std::string& instance_name, + const NodeConfig& conf, + const RosNodeParams& params) + : BT::ActionNodeBase(instance_name, conf) + , node_(params.nh) + , service_timeout_(params.server_timeout) + , wait_for_service_timeout_(params.wait_for_server_timeout) { // check port remapping auto portIt = config().input_ports.find("service_name"); @@ -182,11 +182,13 @@ template inline if(bb_service_name.empty() || bb_service_name == "__default__placeholder__") { - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [service_name] in the InputPort and the RosNodeParams are empty."); + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [service_name] in the InputPort and the " + "RosNodeParams are empty."); } - else { + else + { createClient(params.default_port_value); } } @@ -197,34 +199,40 @@ template inline // create the client in the constructor. createClient(bb_service_name); } - else { + else + { service_name_may_change_ = true; // createClient will be invoked in the first tick(). } } - else { - - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [service_name] in the InputPort and the RosNodeParams are empty."); + else + { + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [service_name] in the InputPort and the RosNodeParams " + "are empty."); } - else { + else + { createClient(params.default_port_value); } } } -template inline - bool RosServiceNode::createClient(const std::string& service_name) +template +inline bool RosServiceNode::createClient(const std::string& service_name) { if(service_name.empty()) { throw RuntimeError("service_name is empty"); } - callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); - service_client_ = node_->create_client(service_name, rmw_qos_profile_services_default, callback_group_); + callback_group_ = + node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + callback_group_executor_.add_callback_group(callback_group_, + node_->get_node_base_interface()); + service_client_ = node_->create_client( + service_name, rmw_qos_profile_services_default, callback_group_); prev_service_name_ = service_name; bool found = service_client_->wait_for_service(wait_for_service_timeout_); @@ -236,8 +244,8 @@ template inline return found; } -template inline - NodeStatus RosServiceNode::tick() +template +inline NodeStatus RosServiceNode::tick() { // First, check if the service_client_ is valid and that the name of the // service_name in the port didn't change. @@ -252,17 +260,17 @@ template inline } } - auto CheckStatus = [](NodeStatus status) - { - if( !isStatusCompleted(status) ) + auto CheckStatus = [](NodeStatus status) { + if(!isStatusCompleted(status)) { - throw std::logic_error("RosServiceNode: the callback must return either SUCCESS or FAILURE"); + throw std::logic_error("RosServiceNode: the callback must return either SUCCESS or " + "FAILURE"); } return status; }; // first step to be done only at the beginning of the Action - if (status() == BT::NodeStatus::IDLE) + if(status() == BT::NodeStatus::IDLE) { setStatus(NodeStatus::RUNNING); @@ -273,9 +281,9 @@ template inline typename Request::SharedPtr request = std::make_shared(); - if( !setRequest(request) ) + if(!setRequest(request)) { - return CheckStatus( onFailure(INVALID_REQUEST) ); + return CheckStatus(onFailure(INVALID_REQUEST)); } // Check if server is ready @@ -288,25 +296,28 @@ template inline return NodeStatus::RUNNING; } - if (status() == NodeStatus::RUNNING) + if(status() == NodeStatus::RUNNING) { callback_group_executor_.spin_some(); // FIRST case: check if the goal request has a timeout - if( !response_received_ ) + if(!response_received_) { auto const nodelay = std::chrono::milliseconds(0); - auto const timeout = rclcpp::Duration::from_seconds( double(service_timeout_.count()) / 1000); + auto const timeout = + rclcpp::Duration::from_seconds(double(service_timeout_.count()) / 1000); - auto ret = callback_group_executor_.spin_until_future_complete(future_response_, nodelay); + auto ret = + callback_group_executor_.spin_until_future_complete(future_response_, nodelay); - if (ret != rclcpp::FutureReturnCode::SUCCESS) + if(ret != rclcpp::FutureReturnCode::SUCCESS) { - if( (node_->now() - time_request_sent_) > timeout ) + if((node_->now() - time_request_sent_) > timeout) { - return CheckStatus( onFailure(SERVICE_TIMEOUT) ); + return CheckStatus(onFailure(SERVICE_TIMEOUT)); } - else{ + else + { return NodeStatus::RUNNING; } } @@ -316,27 +327,26 @@ template inline response_ = future_response_.get(); future_response_ = {}; - if (!response_) { + if(!response_) + { throw std::runtime_error("Request was rejected by the service"); } } } // SECOND case: response received - return CheckStatus( onResponseReceived( response_ ) ); + return CheckStatus(onResponseReceived(response_)); } return NodeStatus::RUNNING; } -template inline - void RosServiceNode::halt() +template +inline void RosServiceNode::halt() { - if( status() == NodeStatus::RUNNING ) + if(status() == NodeStatus::RUNNING) { resetStatus(); } } - } // namespace BT - diff --git a/behaviortree_ros2/include/behaviortree_ros2/bt_topic_pub_node.hpp b/behaviortree_ros2/include/behaviortree_ros2/bt_topic_pub_node.hpp index ebeb1f5..282259e 100644 --- a/behaviortree_ros2/include/behaviortree_ros2/bt_topic_pub_node.hpp +++ b/behaviortree_ros2/include/behaviortree_ros2/bt_topic_pub_node.hpp @@ -29,10 +29,9 @@ namespace BT * @brief Abstract class to wrap a ROS publisher * */ -template +template class RosTopicPubNode : public BT::ConditionNode { - public: // Type definitions using Publisher = typename rclcpp::Publisher; @@ -44,8 +43,7 @@ class RosTopicPubNode : public BT::ConditionNode * * Note that if the external_action_client is not set, the constructor will build its own. * */ - explicit RosTopicPubNode(const std::string & instance_name, - const BT::NodeConfig& conf, + explicit RosTopicPubNode(const std::string& instance_name, const BT::NodeConfig& conf, const RosNodeParams& params); virtual ~RosTopicPubNode() = default; @@ -59,9 +57,8 @@ class RosTopicPubNode : public BT::ConditionNode */ static PortsList providedBasicPorts(PortsList addition) { - PortsList basic = { - InputPort("topic_name", "__default__placeholder__", "Topic name") - }; + PortsList basic = { InputPort("topic_name", "__default__placeholder__", + "Topic name") }; basic.insert(addition.begin(), addition.end()); return basic; } @@ -88,13 +85,11 @@ class RosTopicPubNode : public BT::ConditionNode virtual bool setMessage(TopicT& msg) = 0; protected: - std::shared_ptr node_; std::string prev_topic_name_; bool topic_name_may_change_ = false; private: - std::shared_ptr publisher_; bool createPublisher(const std::string& topic_name); @@ -104,13 +99,12 @@ class RosTopicPubNode : public BT::ConditionNode //---------------------- DEFINITIONS ----------------------------- //---------------------------------------------------------------- -template inline - RosTopicPubNode::RosTopicPubNode(const std::string & instance_name, - const NodeConfig &conf, - const RosNodeParams& params) - : BT::ConditionNode(instance_name, conf), - node_(params.nh) -{ +template +inline RosTopicPubNode::RosTopicPubNode(const std::string& instance_name, + const NodeConfig& conf, + const RosNodeParams& params) + : BT::ConditionNode(instance_name, conf), node_(params.nh) +{ // check port remapping auto portIt = config().input_ports.find("topic_name"); if(portIt != config().input_ports.end()) @@ -119,11 +113,13 @@ template inline if(bb_topic_name.empty() || bb_topic_name == "__default__placeholder__") { - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [topic_name] in the InputPort and the RosNodeParams are empty."); + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [topic_name] in the InputPort and the RosNodeParams " + "are empty."); } - else { + else + { createPublisher(params.default_port_value); } } @@ -134,37 +130,41 @@ template inline // create the client in the constructor. createPublisher(bb_topic_name); } - else { + else + { topic_name_may_change_ = true; // createPublisher will be invoked in the first tick(). } } - else { - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [topic_name] in the InputPort and the RosNodeParams are empty."); + else + { + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [topic_name] in the InputPort and the RosNodeParams " + "are empty."); } - else { + else + { createPublisher(params.default_port_value); } } } -template inline - bool RosTopicPubNode::createPublisher(const std::string& topic_name) +template +inline bool RosTopicPubNode::createPublisher(const std::string& topic_name) { if(topic_name.empty()) { throw RuntimeError("topic_name is empty"); } - + publisher_ = node_->create_publisher(topic_name, 1); prev_topic_name_ = topic_name; return true; } -template inline - NodeStatus RosTopicPubNode::tick() +template +inline NodeStatus RosTopicPubNode::tick() { // First, check if the subscriber_ is valid and that the name of the // topic_name in the port didn't change. @@ -180,7 +180,7 @@ template inline } T msg; - if (!setMessage(msg)) + if(!setMessage(msg)) { return NodeStatus::FAILURE; } @@ -189,4 +189,3 @@ template inline } } // namespace BT - diff --git a/behaviortree_ros2/include/behaviortree_ros2/bt_topic_sub_node.hpp b/behaviortree_ros2/include/behaviortree_ros2/bt_topic_sub_node.hpp index 598859b..42917b1 100644 --- a/behaviortree_ros2/include/behaviortree_ros2/bt_topic_sub_node.hpp +++ b/behaviortree_ros2/include/behaviortree_ros2/bt_topic_sub_node.hpp @@ -27,7 +27,6 @@ namespace BT { - /** * @brief Abstract class to wrap a Topic subscriber. * Considering the example in the tutorial: @@ -42,43 +41,40 @@ namespace BT * 1. If a value is passes in the InputPort "topic_name", use that * 2. Otherwise, use the value in RosNodeParams::default_port_value */ -template +template class RosTopicSubNode : public BT::ConditionNode { - public: +public: // Type definitions using Subscriber = typename rclcpp::Subscription; - protected: +protected: struct SubscriberInstance { void init(std::shared_ptr node, const std::string& topic_name) { // create a callback group for this particular instance - callback_group = - node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); - callback_group_executor.add_callback_group( - callback_group, node->get_node_base_interface()); + callback_group = node->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, false); + callback_group_executor.add_callback_group(callback_group, + node->get_node_base_interface()); rclcpp::SubscriptionOptions option; option.callback_group = callback_group; - // The callback will broadcast to all the instances of RosTopicSubNode - auto callback = [this](const std::shared_ptr msg) - { + // The callback will broadcast to all the instances of RosTopicSubNode + auto callback = [this](const std::shared_ptr msg) { last_msg = msg; broadcaster(msg); }; - subscriber = node->create_subscription(topic_name, 1, callback, option); + subscriber = node->create_subscription(topic_name, 1, callback, option); } std::shared_ptr subscriber; rclcpp::CallbackGroup::SharedPtr callback_group; rclcpp::executors::SingleThreadedExecutor callback_group_executor; - boost::signals2::signal)> broadcaster; + boost::signals2::signal)> broadcaster; std::shared_ptr last_msg; - - }; static std::mutex& registryMutex() @@ -88,9 +84,11 @@ class RosTopicSubNode : public BT::ConditionNode } // contains the fully-qualified name of the node and the name of the topic - static std::unordered_map>& getRegistry() + static std::unordered_map>& + getRegistry() { - static std::unordered_map> subscribers_registry; + static std::unordered_map> + subscribers_registry; return subscribers_registry; } @@ -106,8 +104,7 @@ class RosTopicSubNode : public BT::ConditionNode return node_->get_logger(); } - public: - +public: /** You are not supposed to instantiate this class directly, the factory will do it. * To register this class into the factory, use: * @@ -115,11 +112,10 @@ class RosTopicSubNode : public BT::ConditionNode * * Note that if the external_action_client is not set, the constructor will build its own. * */ - explicit RosTopicSubNode(const std::string & instance_name, - const BT::NodeConfig& conf, + explicit RosTopicSubNode(const std::string& instance_name, const BT::NodeConfig& conf, const RosNodeParams& params); - virtual ~RosTopicSubNode() + virtual ~RosTopicSubNode() { signal_connection_.disconnect(); // remove the subscribers from the static registry when the ALL the @@ -135,7 +131,7 @@ class RosTopicSubNode : public BT::ConditionNode if(it != registry.end() && it->second.use_count() <= 1) { registry.erase(it); - RCLCPP_INFO(logger(), "Remove subscriber [%s]", topic_name_.c_str() ); + RCLCPP_INFO(logger(), "Remove subscriber [%s]", topic_name_.c_str()); } } } @@ -148,9 +144,8 @@ class RosTopicSubNode : public BT::ConditionNode */ static PortsList providedBasicPorts(PortsList addition) { - PortsList basic = { - InputPort("topic_name", "__default__placeholder__", "Topic name") - }; + PortsList basic = { InputPort("topic_name", "__default__placeholder__", + "Topic name") }; basic.insert(addition.begin(), addition.end()); return basic; } @@ -170,23 +165,25 @@ class RosTopicSubNode : public BT::ConditionNode * * @param last_msg the latest message received, since the last tick. * Will be empty if no new message received. - * + * * @return the new status of the Node, based on last_msg */ virtual NodeStatus onTick(const std::shared_ptr& last_msg) = 0; - /** latch the message that has been processed. If returns false and no new message is + /** latch the message that has been processed. If returns false and no new message is * received, before next call there will be no message to process. If returns true, * the next call will process the same message again, if no new message received. - * + * * This can be equated with latched vs non-latched topics in ros 1. - * + * * @return false will clear the message after ticking/processing. */ - virtual bool latchLastMessage() const { return false; } + virtual bool latchLastMessage() const + { + return false; + } private: - bool createSubscriber(const std::string& topic_name); }; @@ -194,13 +191,12 @@ class RosTopicSubNode : public BT::ConditionNode //---------------------- DEFINITIONS ----------------------------- //---------------------------------------------------------------- -template inline - RosTopicSubNode::RosTopicSubNode(const std::string & instance_name, - const NodeConfig &conf, - const RosNodeParams& params) - : BT::ConditionNode(instance_name, conf), - node_(params.nh) -{ +template +inline RosTopicSubNode::RosTopicSubNode(const std::string& instance_name, + const NodeConfig& conf, + const RosNodeParams& params) + : BT::ConditionNode(instance_name, conf), node_(params.nh) +{ // check port remapping auto portIt = config().input_ports.find("topic_name"); if(portIt != config().input_ports.end()) @@ -209,11 +205,13 @@ template inline if(bb_topic_name.empty() || bb_topic_name == "__default__placeholder__") { - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [topic_name] in the InputPort and the RosNodeParams are empty."); + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [topic_name] in the InputPort and the RosNodeParams " + "are empty."); } - else { + else + { createSubscriber(params.default_port_value); } } @@ -224,24 +222,28 @@ template inline // create the client in the constructor. createSubscriber(bb_topic_name); } - else { + else + { // do nothing // createSubscriber will be invoked in the first tick(). } } - else { - if(params.default_port_value.empty()) { - throw std::logic_error( - "Both [topic_name] in the InputPort and the RosNodeParams are empty."); + else + { + if(params.default_port_value.empty()) + { + throw std::logic_error("Both [topic_name] in the InputPort and the RosNodeParams " + "are empty."); } - else { + else + { createSubscriber(params.default_port_value); } } } -template inline - bool RosTopicSubNode::createSubscriber(const std::string& topic_name) +template +inline bool RosTopicSubNode::createSubscriber(const std::string& topic_name) { if(topic_name.empty()) { @@ -260,35 +262,35 @@ template inline auto it = registry.find(subscriber_key_); if(it == registry.end()) { - it = registry.insert( {subscriber_key_, std::make_shared() }).first; + it = registry.insert({ subscriber_key_, std::make_shared() }) + .first; sub_instance_ = it->second; sub_instance_->init(node_, topic_name); - RCLCPP_INFO(logger(), - "Node [%s] created Subscriber to topic [%s]", - name().c_str(), topic_name.c_str() ); + RCLCPP_INFO(logger(), "Node [%s] created Subscriber to topic [%s]", name().c_str(), + topic_name.c_str()); } - else { + else + { sub_instance_ = it->second; } // Check if there was a message received before the creation of this subscriber action - if (sub_instance_->last_msg) + if(sub_instance_->last_msg) { last_msg_ = sub_instance_->last_msg; } // add "this" as received of the broadcaster signal_connection_ = sub_instance_->broadcaster.connect( - [this](const std::shared_ptr msg) { last_msg_ = msg; } ); + [this](const std::shared_ptr msg) { last_msg_ = msg; }); topic_name_ = topic_name; return true; } - -template inline - NodeStatus RosTopicSubNode::tick() +template +inline NodeStatus RosTopicSubNode::tick() { // First, check if the subscriber_ is valid and that the name of the // topic_name in the port didn't change. @@ -296,28 +298,28 @@ template inline std::string topic_name; getInput("topic_name", topic_name); - if(!topic_name.empty() && topic_name != "__default__placeholder__" && topic_name != topic_name_) + if(!topic_name.empty() && topic_name != "__default__placeholder__" && + topic_name != topic_name_) { sub_instance_.reset(); } if(!sub_instance_) { - createSubscriber(topic_name); + createSubscriber(topic_name); } - auto CheckStatus = [](NodeStatus status) - { - if( !isStatusCompleted(status) ) + auto CheckStatus = [](NodeStatus status) { + if(!isStatusCompleted(status)) { - throw std::logic_error("RosTopicSubNode: the callback must return" + throw std::logic_error("RosTopicSubNode: the callback must return" "either SUCCESS or FAILURE"); } return status; }; sub_instance_->callback_group_executor.spin_some(); - auto status = CheckStatus (onTick(last_msg_)); - if (!latchLastMessage()) + auto status = CheckStatus(onTick(last_msg_)); + if(!latchLastMessage()) { last_msg_.reset(); } @@ -325,4 +327,3 @@ template inline } } // namespace BT - diff --git a/behaviortree_ros2/include/behaviortree_ros2/plugins.hpp b/behaviortree_ros2/include/behaviortree_ros2/plugins.hpp index d94f529..4d7ed4d 100644 --- a/behaviortree_ros2/include/behaviortree_ros2/plugins.hpp +++ b/behaviortree_ros2/include/behaviortree_ros2/plugins.hpp @@ -20,7 +20,6 @@ #include "behaviortree_cpp/utils/shared_library.h" #include "behaviortree_ros2/ros_node_params.hpp" - // Use this macro to generate a plugin for: // // - BT::RosActionNode @@ -34,14 +33,12 @@ // Usage example: // CreateRosNodePlugin(MyClassName, "MyClassName"); -#define CreateRosNodePlugin(TYPE, REGISTRATION_NAME) \ -BTCPP_EXPORT void \ -BT_RegisterRosNodeFromPlugin(BT::BehaviorTreeFactory& factory, \ - const BT::RosNodeParams& params) \ -{ \ - factory.registerNodeType(REGISTRATION_NAME, params); \ -} \ - +#define CreateRosNodePlugin(TYPE, REGISTRATION_NAME) \ + BTCPP_EXPORT void BT_RegisterRosNodeFromPlugin(BT::BehaviorTreeFactory& factory, \ + const BT::RosNodeParams& params) \ + { \ + factory.registerNodeType(REGISTRATION_NAME, params); \ + } /** * @brief RegisterRosNode function used to load a plugin and register @@ -51,18 +48,12 @@ BT_RegisterRosNodeFromPlugin(BT::BehaviorTreeFactory& factory, \ * @param filepath path to the plugin. * @param params parameters to pass to the instances of the Node. */ -inline -void RegisterRosNode(BT::BehaviorTreeFactory& factory, - const std::filesystem::path& filepath, - const BT::RosNodeParams& params) +inline void RegisterRosNode(BT::BehaviorTreeFactory& factory, + const std::filesystem::path& filepath, + const BT::RosNodeParams& params) { BT::SharedLibrary loader(filepath.generic_string()); - typedef void (*Func)(BT::BehaviorTreeFactory&, - const BT::RosNodeParams&); + typedef void (*Func)(BT::BehaviorTreeFactory&, const BT::RosNodeParams&); auto func = (Func)loader.getSymbol("BT_RegisterRosNodeFromPlugin"); func(factory, params); } - - - - diff --git a/behaviortree_ros2/include/behaviortree_ros2/ros_node_params.hpp b/behaviortree_ros2/include/behaviortree_ros2/ros_node_params.hpp index 148c086..6ac9e63 100644 --- a/behaviortree_ros2/include/behaviortree_ros2/ros_node_params.hpp +++ b/behaviortree_ros2/include/behaviortree_ros2/ros_node_params.hpp @@ -42,4 +42,4 @@ struct RosNodeParams std::chrono::milliseconds wait_for_server_timeout = std::chrono::milliseconds(500); }; -} +} // namespace BT diff --git a/btcpp_ros2_samples/CMakeLists.txt b/btcpp_ros2_samples/CMakeLists.txt index 1ff82b7..6d4987b 100644 --- a/btcpp_ros2_samples/CMakeLists.txt +++ b/btcpp_ros2_samples/CMakeLists.txt @@ -10,7 +10,7 @@ find_package(behaviortree_ros2 REQUIRED) find_package(std_msgs REQUIRED) find_package(btcpp_ros2_interfaces REQUIRED) -set(THIS_PACKAGE_DEPS +set(THIS_PACKAGE_DEPS behaviortree_ros2 std_msgs btcpp_ros2_interfaces ) @@ -18,7 +18,7 @@ set(THIS_PACKAGE_DEPS ###################################################### # Build a client that call the sleep action (STATIC version) -add_executable(sleep_client +add_executable(sleep_client src/sleep_action.cpp src/sleep_client.cpp) ament_target_dependencies(sleep_client ${THIS_PACKAGE_DEPS}) @@ -38,12 +38,12 @@ ament_target_dependencies(sleep_client_dyn ${THIS_PACKAGE_DEPS}) ###################################################### # Build Server add_executable(sleep_server src/sleep_server.cpp) -ament_target_dependencies(sleep_server ${THIS_PACKAGE_DEPS}) +ament_target_dependencies(sleep_server ${THIS_PACKAGE_DEPS}) ###################################################### # Build subscriber_test add_executable(subscriber_test src/subscriber_test.cpp) -ament_target_dependencies(subscriber_test ${THIS_PACKAGE_DEPS}) +ament_target_dependencies(subscriber_test ${THIS_PACKAGE_DEPS}) ###################################################### # INSTALL diff --git a/btcpp_ros2_samples/src/sleep_action.cpp b/btcpp_ros2_samples/src/sleep_action.cpp index cd28420..1460806 100644 --- a/btcpp_ros2_samples/src/sleep_action.cpp +++ b/btcpp_ros2_samples/src/sleep_action.cpp @@ -1,30 +1,31 @@ #include "sleep_action.hpp" #include "behaviortree_ros2/plugins.hpp" -bool SleepAction::setGoal(RosActionNode::Goal &goal) +bool SleepAction::setGoal(RosActionNode::Goal& goal) { auto timeout = getInput("msec"); goal.msec_timeout = timeout.value(); return true; } -NodeStatus SleepAction::onResultReceived(const RosActionNode::WrappedResult &wr) +NodeStatus SleepAction::onResultReceived(const RosActionNode::WrappedResult& wr) { - RCLCPP_INFO( node_->get_logger(), "%s: onResultReceived. Done = %s", name().c_str(), - wr.result->done ? "true" : "false" ); + RCLCPP_INFO(node_->get_logger(), "%s: onResultReceived. Done = %s", name().c_str(), + wr.result->done ? "true" : "false"); return wr.result->done ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } NodeStatus SleepAction::onFailure(ActionNodeErrorCode error) { - RCLCPP_ERROR( node_->get_logger(), "%s: onFailure with error: %s", name().c_str(), toStr(error) ); + RCLCPP_ERROR(node_->get_logger(), "%s: onFailure with error: %s", name().c_str(), + toStr(error)); return NodeStatus::FAILURE; } void SleepAction::onHalt() { - RCLCPP_INFO( node_->get_logger(), "%s: onHalt", name().c_str() ); + RCLCPP_INFO(node_->get_logger(), "%s: onHalt", name().c_str()); } // Plugin registration. diff --git a/btcpp_ros2_samples/src/sleep_action.hpp b/btcpp_ros2_samples/src/sleep_action.hpp index 4cda7e3..84ec3a8 100644 --- a/btcpp_ros2_samples/src/sleep_action.hpp +++ b/btcpp_ros2_samples/src/sleep_action.hpp @@ -3,18 +3,17 @@ using namespace BT; -class SleepAction: public RosActionNode +class SleepAction : public RosActionNode { public: - SleepAction(const std::string& name, - const NodeConfig& conf, + SleepAction(const std::string& name, const NodeConfig& conf, const RosNodeParams& params) : RosActionNode(name, conf, params) {} static BT::PortsList providedPorts() { - return providedBasicPorts({InputPort("msec")}); + return providedBasicPorts({ InputPort("msec") }); } bool setGoal(Goal& goal) override; diff --git a/btcpp_ros2_samples/src/sleep_client.cpp b/btcpp_ros2_samples/src/sleep_client.cpp index 2290f7e..59f04d0 100644 --- a/btcpp_ros2_samples/src/sleep_client.cpp +++ b/btcpp_ros2_samples/src/sleep_client.cpp @@ -18,29 +18,34 @@ class PrintValue : public BT::SyncActionNode { public: PrintValue(const std::string& name, const BT::NodeConfig& config) - : BT::SyncActionNode(name, config) {} + : BT::SyncActionNode(name, config) + {} - BT::NodeStatus tick() override { + BT::NodeStatus tick() override + { std::string msg; - if( getInput("message", msg ) ){ + if(getInput("message", msg)) + { std::cout << "PrintValue: " << msg << std::endl; return NodeStatus::SUCCESS; } - else{ - std::cout << "PrintValue FAILED "<< std::endl; + else + { + std::cout << "PrintValue FAILED " << std::endl; return NodeStatus::FAILURE; } } - static BT::PortsList providedPorts() { + static BT::PortsList providedPorts() + { return { BT::InputPort("message") }; } }; //----------------------------------------------------- - // Simple tree, used to execute once each action. - static const char* xml_text = R"( +// Simple tree, used to execute once each action. +static const char* xml_text = R"( @@ -58,7 +63,7 @@ class PrintValue : public BT::SyncActionNode )"; -int main(int argc, char **argv) +int main(int argc, char** argv) { rclcpp::init(argc, argv); auto nh = std::make_shared("sleep_client"); @@ -79,7 +84,8 @@ int main(int argc, char **argv) auto tree = factory.createTreeFromText(xml_text); - for(int i=0; i<5; i++){ + for(int i = 0; i < 5; i++) + { tree.tickWhileRunning(); } diff --git a/btcpp_ros2_samples/src/sleep_server.cpp b/btcpp_ros2_samples/src/sleep_server.cpp index d7c97ef..c13f8f3 100644 --- a/btcpp_ros2_samples/src/sleep_server.cpp +++ b/btcpp_ros2_samples/src/sleep_server.cpp @@ -13,32 +13,30 @@ class SleepActionServer : public rclcpp::Node using Sleep = btcpp_ros2_interfaces::action::Sleep; using GoalHandleSleep = rclcpp_action::ServerGoalHandle; - explicit SleepActionServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()) + explicit SleepActionServer(const rclcpp::NodeOptions& options = rclcpp::NodeOptions()) : Node("sleep_action_server", options) { using namespace std::placeholders; this->action_server_ = rclcpp_action::create_server( - this, - "sleep_service", - std::bind(&SleepActionServer::handle_goal, this, _1, _2), - std::bind(&SleepActionServer::handle_cancel, this, _1), - std::bind(&SleepActionServer::handle_accepted, this, _1)); + this, "sleep_service", std::bind(&SleepActionServer::handle_goal, this, _1, _2), + std::bind(&SleepActionServer::handle_cancel, this, _1), + std::bind(&SleepActionServer::handle_accepted, this, _1)); } private: rclcpp_action::Server::SharedPtr action_server_; - rclcpp_action::GoalResponse handle_goal( - const rclcpp_action::GoalUUID &, - std::shared_ptr goal) + rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID&, + std::shared_ptr goal) { - RCLCPP_INFO(this->get_logger(), "Received goal request with sleep time %d", goal->msec_timeout); + RCLCPP_INFO(this->get_logger(), "Received goal request with sleep time %d", + goal->msec_timeout); return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } - rclcpp_action::CancelResponse handle_cancel( - const std::shared_ptr goal_handle) + rclcpp_action::CancelResponse + handle_cancel(const std::shared_ptr goal_handle) { RCLCPP_INFO(this->get_logger(), "Received request to cancel goal"); (void)goal_handle; @@ -49,7 +47,7 @@ class SleepActionServer : public rclcpp::Node { using namespace std::placeholders; // this needs to return quickly to avoid blocking the executor, so spin up a new thread - std::thread{std::bind(&SleepActionServer::execute, this, _1), goal_handle}.detach(); + std::thread{ std::bind(&SleepActionServer::execute, this, _1), goal_handle }.detach(); } void execute(const std::shared_ptr goal_handle) @@ -60,12 +58,13 @@ class SleepActionServer : public rclcpp::Node auto feedback = std::make_shared(); auto result = std::make_shared(); - rclcpp::Time deadline = get_clock()->now() + rclcpp::Duration::from_seconds( double(goal->msec_timeout) / 1000 ); + rclcpp::Time deadline = get_clock()->now() + rclcpp::Duration::from_seconds( + double(goal->msec_timeout) / 1000); int cycle = 0; - while( get_clock()->now() < deadline ) + while(get_clock()->now() < deadline) { - if (goal_handle->is_canceling()) + if(goal_handle->is_canceling()) { result->done = false; goal_handle->canceled(result); @@ -81,7 +80,7 @@ class SleepActionServer : public rclcpp::Node } // Check if goal is done - if (rclcpp::ok()) + if(rclcpp::ok()) { result->done = true; goal_handle->succeed(result); @@ -90,7 +89,6 @@ class SleepActionServer : public rclcpp::Node } }; // class SleepActionServer - int main(int argc, char** argv) { rclcpp::init(argc, argv); diff --git a/btcpp_ros2_samples/src/subscriber_test.cpp b/btcpp_ros2_samples/src/subscriber_test.cpp index 195f1b9..3cd9240 100644 --- a/btcpp_ros2_samples/src/subscriber_test.cpp +++ b/btcpp_ros2_samples/src/subscriber_test.cpp @@ -3,11 +3,10 @@ using namespace BT; -class ReceiveString: public RosTopicSubNode +class ReceiveString : public RosTopicSubNode { public: - ReceiveString(const std::string& name, - const NodeConfig& conf, + ReceiveString(const std::string& name, const NodeConfig& conf, const RosNodeParams& params) : RosTopicSubNode(name, conf, params) {} @@ -19,16 +18,17 @@ class ReceiveString: public RosTopicSubNode NodeStatus onTick(const std::shared_ptr& last_msg) override { - if(last_msg) // empty if no new message received, since the last tick + if(last_msg) // empty if no new message received, since the last tick { - RCLCPP_INFO(logger(), "[%s] new message: %s", name().c_str(), last_msg->data.c_str()); + RCLCPP_INFO(logger(), "[%s] new message: %s", name().c_str(), + last_msg->data.c_str()); } return NodeStatus::SUCCESS; } }; - // Simple tree, used to execute once each action. - static const char* xml_text = R"( +// Simple tree, used to execute once each action. +static const char* xml_text = R"( @@ -40,7 +40,7 @@ class ReceiveString: public RosTopicSubNode )"; -int main(int argc, char **argv) +int main(int argc, char** argv) { rclcpp::init(argc, argv); auto nh = std::make_shared("subscriber_test");