From 41327aef7f922559d930108cd87c1d4561597f98 Mon Sep 17 00:00:00 2001 From: corot Date: Tue, 21 Nov 2023 14:23:27 +0900 Subject: [PATCH] clang format --- .../mbf_abstract_nav/controller_action.h | 38 +++++++------------ .../include/mbf_abstract_nav/planner_action.h | 27 +++++-------- .../src/abstract_controller_execution.cpp | 20 +++++----- .../costmap_controller_execution.cpp | 17 ++++----- 4 files changed, 41 insertions(+), 61 deletions(-) diff --git a/mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h b/mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h index 0046a1f0..3d8ca7ac 100644 --- a/mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h +++ b/mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h @@ -52,15 +52,12 @@ namespace mbf_abstract_nav { -class ControllerAction : - public AbstractActionBase +class ControllerAction : public AbstractActionBase { - public: - +public: typedef boost::shared_ptr Ptr; - ControllerAction(const std::string &name, - const mbf_utility::RobotInformation &robot_info); + ControllerAction(const std::string& name, const mbf_utility::RobotInformation& robot_info); /** * @brief Start controller action. @@ -68,18 +65,13 @@ class ControllerAction : * @param goal_handle Reference to the goal handle received on action execution callback. * @param execution_ptr Pointer to the execution descriptor. */ - void start( - GoalHandle &goal_handle, - typename AbstractControllerExecution::Ptr execution_ptr - ); + void start(GoalHandle& goal_handle, typename AbstractControllerExecution::Ptr execution_ptr); - void runImpl(GoalHandle &goal_handle, AbstractControllerExecution& execution); + void runImpl(GoalHandle& goal_handle, AbstractControllerExecution& execution); protected: - void publishExePathFeedback( - GoalHandle &goal_handle, - uint32_t outcome, const std::string &message, - const geometry_msgs::TwistStamped ¤t_twist); + void publishExePathFeedback(GoalHandle& goal_handle, uint32_t outcome, const std::string& message, + const geometry_msgs::TwistStamped& current_twist); /** * @brief Utility method to fill the ExePath action result in a single line @@ -87,19 +79,15 @@ class ControllerAction : * @param message ExePath action message * @param result The action result to fill */ - void fillExePathResult( - uint32_t outcome, const std::string &message, - mbf_msgs::ExePathResult &result); + void fillExePathResult(uint32_t outcome, const std::string& message, mbf_msgs::ExePathResult& result); - boost::mutex goal_mtx_; ///< lock goal handle for updating it while running - geometry_msgs::PoseStamped robot_pose_; ///< Current robot pose - geometry_msgs::PoseStamped goal_pose_; ///< Current goal pose + boost::mutex goal_mtx_; ///< lock goal handle for updating it while running + geometry_msgs::PoseStamped robot_pose_; ///< Current robot pose + geometry_msgs::PoseStamped goal_pose_; ///< Current goal pose //! Publish the current goal pose (the last pose of the path we are following) ros::Publisher goal_pub_; }; -} - - +} // namespace mbf_abstract_nav -#endif //MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_ +#endif // MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_ diff --git a/mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h b/mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h index 7f6cdf9c..3a1be0a8 100644 --- a/mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h +++ b/mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h @@ -49,36 +49,29 @@ #include "mbf_abstract_nav/abstract_action_base.hpp" #include "mbf_abstract_nav/abstract_planner_execution.h" - -namespace mbf_abstract_nav{ - +namespace mbf_abstract_nav +{ class PlannerAction : public AbstractActionBase { - public: - +public: typedef boost::shared_ptr Ptr; - PlannerAction( - const std::string &name, - const mbf_utility::RobotInformation &robot_info - ); - - void runImpl(GoalHandle &goal_handle, AbstractPlannerExecution &execution); + PlannerAction(const std::string& name, const mbf_utility::RobotInformation& robot_info); - protected: + void runImpl(GoalHandle& goal_handle, AbstractPlannerExecution& execution); +protected: /** * @brief Transforms a plan to the global frame (global_frame_) coord system. * @param plan Input plan to be transformed. * @param global_plan Output plan, which is then transformed to the global frame. * @return true, if the transformation succeeded, false otherwise */ - bool transformPlanToGlobalFrame(const std::vector& plan, - std::vector& global_plan); - - private: + bool transformPlanToGlobalFrame(const std::vector& plan, + std::vector& global_plan); +private: //! Publisher to publish the current goal pose, which is used for path planning ros::Publisher goal_pub_; @@ -86,6 +79,6 @@ class PlannerAction : public AbstractActionBase