diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index d400b031d0..bbb39c5358 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -1581,17 +1581,20 @@ AmclNode::initServices() { global_loc_srv_ = create_service( "reinitialize_global_localization", - std::bind(&AmclNode::globalLocalizationCallback, this, std::placeholders::_1, + std::bind( + &AmclNode::globalLocalizationCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); initial_guess_srv_ = create_service( "set_initial_pose", - std::bind(&AmclNode::initialPoseReceivedSrv, this, std::placeholders::_1, std::placeholders::_2, + std::bind( + &AmclNode::initialPoseReceivedSrv, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); nomotion_update_srv_ = create_service( "request_nomotion_update", - std::bind(&AmclNode::nomotionUpdateCallback, this, std::placeholders::_1, std::placeholders::_2, + std::bind( + &AmclNode::nomotionUpdateCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); } diff --git a/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp b/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp index cab0311a37..ce042d1f3b 100644 --- a/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp +++ b/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp @@ -46,12 +46,12 @@ inline BT::NodeStatus GetPoseFromPath::tick() } // Account for negative indices - if(pose_index < 0) { + if (pose_index < 0) { pose_index = input_path.poses.size() + pose_index; } // out of bounds index - if(pose_index < 0 || static_cast(pose_index) >= input_path.poses.size()) { + if (pose_index < 0 || static_cast(pose_index) >= input_path.poses.size()) { return BT::NodeStatus::FAILURE; } @@ -60,7 +60,7 @@ inline BT::NodeStatus GetPoseFromPath::tick() output_pose = input_path.poses[pose_index]; // populate pose frame from path if necessary - if(output_pose.header.frame_id.empty()) { + if (output_pose.header.frame_id.empty()) { output_pose.header.frame_id = input_path.header.frame_id; } diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 80721bb5b3..d71cfccde4 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -256,7 +256,8 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) // Service to get the cost at a point get_cost_service_ = create_service( "get_cost_" + getName(), - std::bind(&Costmap2DROS::getCostCallback, this, std::placeholders::_1, std::placeholders::_2, + std::bind( + &Costmap2DROS::getCostCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); // Add cleaning service @@ -423,7 +424,7 @@ Costmap2DROS::getParameters() std::size_t first_slash = raw_namespace.find('/', 1); std::string robot_namespace = ""; if (first_slash != std::string::npos) { - robot_namespace = raw_namespace.substr(1, first_slash - 1) + "/"; + robot_namespace = raw_namespace.substr(1, first_slash - 1) + "/"; } global_frame_ = robot_namespace + nav2_util::strip_leading_slash(global_frame_); diff --git a/nav2_rviz_plugins/src/costmap_cost_tool.cpp b/nav2_rviz_plugins/src/costmap_cost_tool.cpp index f25a71cd80..57fe5a5399 100644 --- a/nav2_rviz_plugins/src/costmap_cost_tool.cpp +++ b/nav2_rviz_plugins/src/costmap_cost_tool.cpp @@ -92,13 +92,15 @@ void CostmapCostTool::callCostService(float x, float y) // Call local costmap service if (local_cost_client_->wait_for_service(std::chrono::seconds(1))) { - local_cost_client_->async_send_request(request, + local_cost_client_->async_send_request( + request, std::bind(&CostmapCostTool::handleLocalCostResponse, this, std::placeholders::_1)); } // Call global costmap service if (global_cost_client_->wait_for_service(std::chrono::seconds(1))) { - global_cost_client_->async_send_request(request, + global_cost_client_->async_send_request( + request, std::bind(&CostmapCostTool::handleGlobalCostResponse, this, std::placeholders::_1)); } }