Skip to content

Commit f067f5f

Browse files
committed
Style fixes
1 parent 945a70e commit f067f5f

File tree

1 file changed

+12
-12
lines changed

1 file changed

+12
-12
lines changed

rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -68,19 +68,19 @@ NodeParameters::NodeParameters(
6868
// Get paths to yaml files containing initial parameter values
6969
std::vector<std::string> yaml_paths;
7070

71-
auto get_yaml_paths = [&yaml_paths, &options] (const rcl_arguments_t * args) {
72-
int num_yaml_files = rcl_arguments_get_param_files_count(args);
73-
if (num_yaml_files > 0) {
74-
char ** param_files;
75-
rcl_ret_t ret = rcl_arguments_get_param_files(args, options->allocator, &param_files);
76-
if (RCL_RET_OK != ret) {
77-
rclcpp::exceptions::throw_from_rcl_error(ret);
78-
}
79-
for (int i = 0; i < num_yaml_files; ++i) {
80-
yaml_paths.emplace_back(param_files[i]);
71+
auto get_yaml_paths = [&yaml_paths, &options](const rcl_arguments_t * args) {
72+
int num_yaml_files = rcl_arguments_get_param_files_count(args);
73+
if (num_yaml_files > 0) {
74+
char ** param_files;
75+
rcl_ret_t ret = rcl_arguments_get_param_files(args, options->allocator, &param_files);
76+
if (RCL_RET_OK != ret) {
77+
rclcpp::exceptions::throw_from_rcl_error(ret);
78+
}
79+
for (int i = 0; i < num_yaml_files; ++i) {
80+
yaml_paths.emplace_back(param_files[i]);
81+
}
8182
}
82-
}
83-
};
83+
};
8484

8585
// global before local so that local overwrites global
8686
if (options->use_global_arguments) {

0 commit comments

Comments
 (0)