Skip to content

Commit

Permalink
Adaptted "ament_uncrustify"
Browse files Browse the repository at this point in the history
  • Loading branch information
KuraZuzu committed Nov 20, 2024
1 parent 3e395d3 commit 182da8d
Show file tree
Hide file tree
Showing 7 changed files with 17 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class CameraFollower : public rclcpp_lifecycle::LifecycleNode
double object_normalized_area_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>> result_image_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>>
cmd_vel_pub_;
cmd_vel_pub_;
std::shared_ptr<rclcpp::Client<std_srvs::srv::SetBool>> motor_power_client_;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_sub_;
rclcpp::Subscription<raspimouse_msgs::msg::Switches>::SharedPtr switches_sub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class Follower : public rclcpp_lifecycle::LifecycleNode

std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::Int16>> buzzer_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>>
cmd_vel_pub_;
cmd_vel_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<raspimouse_msgs::msg::Leds>> leds_pub_;
rclcpp::Subscription<raspimouse_msgs::msg::LightSensors>::SharedPtr light_sensors_sub_;
rclcpp::Subscription<raspimouse_msgs::msg::Switches>::SharedPtr switches_sub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class Tracker : public rclcpp_lifecycle::LifecycleNode
geometry_msgs::msg::TwistStamped cmd_vel_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>> result_image_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>>
cmd_vel_pub_;
cmd_vel_pub_;
std::shared_ptr<rclcpp::Client<std_srvs::srv::SetBool>> motor_power_client_;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_sub_;
rclcpp::TimerBase::SharedPtr cmd_vel_timer_;
Expand Down
3 changes: 2 additions & 1 deletion src/camera_line_follower_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
7 changes: 4 additions & 3 deletions src/direction_controller_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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...

Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -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)
{
Expand Down
10 changes: 5 additions & 5 deletions src/lifecycle_node_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,23 +60,23 @@ bool all_nodes_are_unconfigured(
rclcpp::Node::SharedPtr node, const std::vector<std::string> & 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;
});
}

bool all_nodes_are_inactive(
rclcpp::Node::SharedPtr node, const std::vector<std::string> & 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;
});
}

bool all_nodes_are_active(
rclcpp::Node::SharedPtr node, const std::vector<std::string> & 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;
});
}

Expand Down Expand Up @@ -112,15 +112,15 @@ bool configure_all_nodes(
rclcpp::Node::SharedPtr node, const std::vector<std::string> & 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);
});
}

bool activate_all_nodes(
rclcpp::Node::SharedPtr node, const std::vector<std::string> & 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);
});
}

Expand Down
6 changes: 3 additions & 3 deletions src/line_follower_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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)
{
Expand Down

0 comments on commit 182da8d

Please sign in to comment.