From 182da8d4650f2b82c9cadf68e33fe29a23c710b9 Mon Sep 17 00:00:00 2001 From: KuraZuzu Date: Wed, 20 Nov 2024 15:15:45 +0900 Subject: [PATCH] Adaptted "ament_uncrustify" --- .../camera_line_follower_component.hpp | 2 +- .../line_follower_component.hpp | 2 +- .../object_tracking_component.hpp | 2 +- src/camera_line_follower_component.cpp | 3 ++- src/direction_controller_component.cpp | 7 ++++--- src/lifecycle_node_manager.cpp | 10 +++++----- src/line_follower_component.cpp | 6 +++--- 7 files changed, 17 insertions(+), 15 deletions(-) diff --git a/include/raspimouse_ros2_examples/camera_line_follower_component.hpp b/include/raspimouse_ros2_examples/camera_line_follower_component.hpp index 5aba27d..16a3a4a 100644 --- a/include/raspimouse_ros2_examples/camera_line_follower_component.hpp +++ b/include/raspimouse_ros2_examples/camera_line_follower_component.hpp @@ -51,7 +51,7 @@ class CameraFollower : public rclcpp_lifecycle::LifecycleNode double object_normalized_area_; std::shared_ptr> result_image_pub_; std::shared_ptr> - cmd_vel_pub_; + cmd_vel_pub_; std::shared_ptr> motor_power_client_; rclcpp::Subscription::SharedPtr image_sub_; rclcpp::Subscription::SharedPtr switches_sub_; diff --git a/include/raspimouse_ros2_examples/line_follower_component.hpp b/include/raspimouse_ros2_examples/line_follower_component.hpp index 77d9663..555d3dd 100644 --- a/include/raspimouse_ros2_examples/line_follower_component.hpp +++ b/include/raspimouse_ros2_examples/line_follower_component.hpp @@ -73,7 +73,7 @@ class Follower : public rclcpp_lifecycle::LifecycleNode std::shared_ptr> buzzer_pub_; std::shared_ptr> - cmd_vel_pub_; + cmd_vel_pub_; std::shared_ptr> leds_pub_; rclcpp::Subscription::SharedPtr light_sensors_sub_; rclcpp::Subscription::SharedPtr switches_sub_; diff --git a/include/raspimouse_ros2_examples/object_tracking_component.hpp b/include/raspimouse_ros2_examples/object_tracking_component.hpp index 9989c7c..3a86f3c 100644 --- a/include/raspimouse_ros2_examples/object_tracking_component.hpp +++ b/include/raspimouse_ros2_examples/object_tracking_component.hpp @@ -49,7 +49,7 @@ class Tracker : public rclcpp_lifecycle::LifecycleNode geometry_msgs::msg::TwistStamped cmd_vel_; std::shared_ptr> result_image_pub_; std::shared_ptr> - cmd_vel_pub_; + cmd_vel_pub_; std::shared_ptr> motor_power_client_; rclcpp::Subscription::SharedPtr image_sub_; rclcpp::TimerBase::SharedPtr cmd_vel_timer_; diff --git a/src/camera_line_follower_component.cpp b/src/camera_line_follower_component.cpp index f5188f7..2a0f89a 100644 --- a/src/camera_line_follower_component.cpp +++ b/src/camera_line_follower_component.cpp @@ -81,7 +81,8 @@ void CameraFollower::on_cmd_vel_timer() // when the number of pixels of the object is greater than the threshold. if ( object_is_detected_ && - object_normalized_area_ > get_parameter(AREA_THRESHOLD_PARAM).as_double()) { + object_normalized_area_ > get_parameter(AREA_THRESHOLD_PARAM).as_double()) + { cmd_vel.twist.linear.x = get_parameter(LINEAR_VEL_PARAM).as_double(); cmd_vel.twist.angular.z = -get_parameter(ANGULAR_VEL_PARAM).as_double() * object_normalized_point_.x; diff --git a/src/direction_controller_component.cpp b/src/direction_controller_component.cpp index a6436ea..7a30510 100644 --- a/src/direction_controller_component.cpp +++ b/src/direction_controller_component.cpp @@ -35,7 +35,8 @@ enum CONTROL_MODE MODE_ROTATION = 3 }; -Controller::Controller(const rclcpp::NodeOptions & options) : Node("direction_controller", options) +Controller::Controller(const rclcpp::NodeOptions & options) +: Node("direction_controller", options) { using namespace std::placeholders; // for _1, _2, _3... @@ -185,7 +186,7 @@ bool Controller::omega_calibration(const double omega) if (omega_samples_.size() >= SAMPLE_NUM) { omega_bias_ = std::accumulate(std::begin(omega_samples_), std::end(omega_samples_), 0.0) / - omega_samples_.size(); + omega_samples_.size(); omega_samples_.clear(); complete = true; } @@ -261,7 +262,7 @@ void Controller::beep_buzzer(const int freq, const std::chrono::nanoseconds & be buzzer_pub_->publish(std::move(msg)); } -void Controller::beep_start(void) { beep_buzzer(1000, 500ms); } +void Controller::beep_start(void) {beep_buzzer(1000, 500ms);} void Controller::beep_success(void) { diff --git a/src/lifecycle_node_manager.cpp b/src/lifecycle_node_manager.cpp index a241f10..12d019f 100644 --- a/src/lifecycle_node_manager.cpp +++ b/src/lifecycle_node_manager.cpp @@ -60,7 +60,7 @@ bool all_nodes_are_unconfigured( rclcpp::Node::SharedPtr node, const std::vector & target_node_names) { return std::all_of(target_node_names.begin(), target_node_names.end(), [&](std::string s) { - return state_of(s, node, 10s) == MsgState::PRIMARY_STATE_UNCONFIGURED; + return state_of(s, node, 10s) == MsgState::PRIMARY_STATE_UNCONFIGURED; }); } @@ -68,7 +68,7 @@ bool all_nodes_are_inactive( rclcpp::Node::SharedPtr node, const std::vector & target_node_names) { return std::all_of(target_node_names.begin(), target_node_names.end(), [&](std::string s) { - return state_of(s, node, 10s) == MsgState::PRIMARY_STATE_INACTIVE; + return state_of(s, node, 10s) == MsgState::PRIMARY_STATE_INACTIVE; }); } @@ -76,7 +76,7 @@ bool all_nodes_are_active( rclcpp::Node::SharedPtr node, const std::vector & target_node_names) { return std::all_of(target_node_names.begin(), target_node_names.end(), [&](std::string s) { - return state_of(s, node, 10s) == MsgState::PRIMARY_STATE_ACTIVE; + return state_of(s, node, 10s) == MsgState::PRIMARY_STATE_ACTIVE; }); } @@ -112,7 +112,7 @@ bool configure_all_nodes( rclcpp::Node::SharedPtr node, const std::vector & target_node_names) { return std::all_of(target_node_names.begin(), target_node_names.end(), [&](std::string s) { - return change_state(s, node, MsgTransition::TRANSITION_CONFIGURE, 10s); + return change_state(s, node, MsgTransition::TRANSITION_CONFIGURE, 10s); }); } @@ -120,7 +120,7 @@ bool activate_all_nodes( rclcpp::Node::SharedPtr node, const std::vector & target_node_names) { return std::all_of(target_node_names.begin(), target_node_names.end(), [&](std::string s) { - return change_state(s, node, MsgTransition::TRANSITION_ACTIVATE, 10s); + return change_state(s, node, MsgTransition::TRANSITION_ACTIVATE, 10s); }); } diff --git a/src/line_follower_component.cpp b/src/line_follower_component.cpp index bd018d9..9375abb 100644 --- a/src/line_follower_component.cpp +++ b/src/line_follower_component.cpp @@ -127,10 +127,10 @@ void Follower::publish_cmdvel_for_line_following(void) bool detect_line = std::any_of( line_is_detected_by_sensor_.begin(), line_is_detected_by_sensor_.end(), - [](bool detected) { return detected; }); + [](bool detected) {return detected;}); bool detect_field = std::any_of( line_is_detected_by_sensor_.begin(), line_is_detected_by_sensor_.end(), - [](bool detected) { return !detected; }); + [](bool detected) {return !detected;}); if (detect_line && detect_field) { cmd_vel->twist.linear.x = VEL_LINEAR_X; @@ -201,7 +201,7 @@ void Follower::beep_buzzer(const int freq, const std::chrono::nanoseconds & beep buzzer_pub_->publish(std::move(msg)); } -void Follower::beep_start(void) { beep_buzzer(1000, 500ms); } +void Follower::beep_start(void) {beep_buzzer(1000, 500ms);} void Follower::beep_success(void) {