Skip to content

Commit

Permalink
Exception safe cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Jun 7, 2018
1 parent ef427a7 commit b9a7e74
Showing 1 changed file with 8 additions and 2 deletions.
10 changes: 8 additions & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "rcl_interfaces/srv/list_parameters.hpp"
#include "rclcpp/create_publisher.hpp"
#include "rclcpp/parameter_map.hpp"
#include "rclcpp/scope_exit.hpp"
#include "rcutils/logging_macros.h"
#include "rmw/qos_profiles.h"

Expand Down Expand Up @@ -76,11 +77,16 @@ NodeParameters::NodeParameters(
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
auto cleanup_param_files = make_scope_exit(
[&param_files, &num_yaml_files, &options]() {
for (int i = 0; i < num_yaml_files; ++i) {
options->allocator.deallocate(param_files[i], options->allocator.state);
}
options->allocator.deallocate(param_files, options->allocator.state);
});
for (int i = 0; i < num_yaml_files; ++i) {
yaml_paths.emplace_back(param_files[i]);
options->allocator.deallocate(param_files[i], options->allocator.state);
}
options->allocator.deallocate(param_files, options->allocator.state);
}
};

Expand Down

0 comments on commit b9a7e74

Please sign in to comment.