Skip to content

Commit 623636c

Browse files
authored
fix some lint issues for humble branch (#5253)
Signed-off-by: Guanxiao Qi <944843236@qq.com>
1 parent 114cda3 commit 623636c

File tree

18 files changed

+46
-35
lines changed

18 files changed

+46
-35
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -212,7 +212,8 @@ class BtActionNode : public BT::ActionNodeBase
212212
// if new goal was sent and action server has not yet responded
213213
// check the future goal handle
214214
if (future_goal_handle_) {
215-
auto elapsed = (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
215+
auto elapsed =
216+
(node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
216217
if (!is_future_goal_handle_complete(elapsed)) {
217218
// return RUNNING if there is still some time before timeout happens
218219
if (elapsed < server_timeout_) {
@@ -242,7 +243,8 @@ class BtActionNode : public BT::ActionNodeBase
242243
{
243244
goal_updated_ = false;
244245
send_new_goal();
245-
auto elapsed = (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
246+
auto elapsed =
247+
(node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
246248
if (!is_future_goal_handle_complete(elapsed)) {
247249
if (elapsed < server_timeout_) {
248250
return BT::NodeStatus::RUNNING;
@@ -472,7 +474,7 @@ class BtActionNode : public BT::ActionNodeBase
472474
std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>
473475
future_goal_handle_;
474476
rclcpp::Time time_goal_sent_;
475-
477+
476478
// Can be set in on_tick or on_wait_for_result to indicate if a goal should be sent.
477479
bool should_send_goal_;
478480
};

nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -46,12 +46,12 @@ inline BT::NodeStatus GetPoseFromPath::tick()
4646
}
4747

4848
// Account for negative indices
49-
if(pose_index < 0) {
49+
if (pose_index < 0) {
5050
pose_index = input_path.poses.size() + pose_index;
5151
}
5252

5353
// out of bounds index
54-
if(pose_index < 0 || static_cast<unsigned>(pose_index) >= input_path.poses.size()) {
54+
if (pose_index < 0 || static_cast<unsigned>(pose_index) >= input_path.poses.size()) {
5555
return BT::NodeStatus::FAILURE;
5656
}
5757

@@ -60,7 +60,7 @@ inline BT::NodeStatus GetPoseFromPath::tick()
6060
output_pose = input_path.poses[pose_index];
6161

6262
// populate pose frame from path if necessary
63-
if(output_pose.header.frame_id.empty()) {
63+
if (output_pose.header.frame_id.empty()) {
6464
output_pose.header.frame_id = input_path.header.frame_id;
6565
}
6666

nav2_behavior_tree/plugins/decorator/speed_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ SpeedController::SpeedController(
4343

4444
if (min_rate_ <= 0.0 || max_rate_ <= 0.0) {
4545
std::string err_msg = "SpeedController node cannot have rate <= 0.0";
46-
RCLCPP_FATAL(node_->get_logger(), "%s" ,err_msg.c_str());
46+
RCLCPP_FATAL(node_->get_logger(), "%s", err_msg.c_str());
4747
throw BT::BehaviorTreeException(err_msg);
4848
}
4949

nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -248,7 +248,8 @@ class DriveOnHeading : public TimedBehavior<ActionT>
248248
node->get_parameter(this->behavior_name_ + ".deceleration_limit", deceleration_limit_);
249249
node->get_parameter(this->behavior_name_ + ".minimum_speed", minimum_speed_);
250250
if (acceleration_limit_ < 0.0 || deceleration_limit_ > 0.0) {
251-
RCLCPP_ERROR(this->logger_,
251+
RCLCPP_ERROR(
252+
this->logger_,
252253
"DriveOnHeading: acceleration_limit and deceleration_limit must be "
253254
"positive and negative respectively");
254255
acceleration_limit_ = std::abs(acceleration_limit_);

nav2_bringup/launch/bringup_launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
from launch_ros.actions import Node
2626
from launch_ros.actions import PushRosNamespace
2727
from launch_ros.descriptions import ParameterFile
28-
from nav2_common.launch import RewrittenYaml, ReplaceString
28+
from nav2_common.launch import ReplaceString, RewrittenYaml
2929

3030

3131
def generate_launch_description():

nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,13 +14,15 @@
1414

1515

1616
import os
17+
1718
from ament_index_python.packages import get_package_share_directory
1819
from launch import LaunchDescription
1920
from launch.actions import (DeclareLaunchArgument, ExecuteProcess, GroupAction,
2021
IncludeLaunchDescription, LogInfo)
2122
from launch.conditions import IfCondition
2223
from launch.launch_description_sources import PythonLaunchDescriptionSource
2324
from launch.substitutions import LaunchConfiguration, TextSubstitution
25+
2426
from nav2_common.launch import ParseMultiRobotPose
2527

2628

nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -86,10 +86,10 @@ class Polygon
8686
* @return Action type for current polygon
8787
*/
8888
ActionType getActionType() const;
89-
/**
90-
* @brief Obtains polygon enabled state
91-
* @return Whether polygon is enabled
92-
*/
89+
/**
90+
* @brief Obtains polygon enabled state
91+
* @return Whether polygon is enabled
92+
*/
9393
bool getEnabled() const;
9494
/**
9595
* @brief Obtains polygon maximum points to enter inside polygon causing no action
@@ -184,7 +184,7 @@ class Polygon
184184
rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")};
185185
/// @brief Dynamic parameters handler
186186
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
187-
187+
188188
// Basic parameters
189189
/// @brief Name of polygon
190190
std::string polygon_name_;

nav2_collision_monitor/src/polygon.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ bool Polygon::configure()
8686
// Add callback for dynamic parameters
8787
dyn_params_handler_ = node->add_on_set_parameters_callback(
8888
std::bind(&Polygon::dynamicParametersCallback, this, std::placeholders::_1));
89-
89+
9090
return true;
9191
}
9292

@@ -257,7 +257,7 @@ bool Polygon::getCommonParameters(std::string & polygon_pub_topic)
257257
nav2_util::declare_parameter_if_not_declared(
258258
node, polygon_name_ + ".enabled", rclcpp::ParameterValue(true));
259259
enabled_ = node->get_parameter(polygon_name_ + ".enabled").as_bool();
260-
260+
261261
nav2_util::declare_parameter_if_not_declared(
262262
node, polygon_name_ + ".max_points", rclcpp::ParameterValue(3));
263263
max_points_ = node->get_parameter(polygon_name_ + ".max_points").as_int();

nav2_collision_monitor/test/collision_monitor_node_test.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -182,11 +182,11 @@ class Tester : public ::testing::Test
182182
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_out_sub_;
183183

184184
geometry_msgs::msg::Twist::SharedPtr cmd_vel_out_;
185-
185+
186186
// CollisionMonitor Action state
187187
rclcpp::Subscription<nav2_msgs::msg::CollisionMonitorState>::SharedPtr action_state_sub_;
188188
nav2_msgs::msg::CollisionMonitorState::SharedPtr action_state_;
189-
189+
190190
// Service client for setting CollisionMonitor parameters
191191
rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedPtr parameters_client_;
192192
}; // Tester
@@ -210,7 +210,7 @@ Tester::Tester()
210210
cmd_vel_out_sub_ = cm_->create_subscription<geometry_msgs::msg::Twist>(
211211
CMD_VEL_OUT_TOPIC, rclcpp::SystemDefaultsQoS(),
212212
std::bind(&Tester::cmdVelOutCallback, this, std::placeholders::_1));
213-
213+
214214
action_state_sub_ = cm_->create_subscription<nav2_msgs::msg::CollisionMonitorState>(
215215
STATE_TOPIC, rclcpp::SystemDefaultsQoS(),
216216
std::bind(&Tester::actionStateCallback, this, std::placeholders::_1));

nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -987,8 +987,9 @@ class GroupsRemover
987987
{
988988
// Creates an image labels in which each obstacles group is labeled with a unique code
989989
Label groups_count;
990-
auto labels = connectedComponents<connectivity>(image, buffer, label_trees,
991-
is_background, groups_count);
990+
auto labels = connectedComponents<connectivity>(
991+
image, buffer, label_trees,
992+
is_background, groups_count);
992993

993994
// Calculates the size of each group.
994995
// Group size is equal to the number of pixels with the same label

0 commit comments

Comments
 (0)