Skip to content

Commit

Permalink
fix(autoware_static_centerline_generator): fix bugprone-exception-esc…
Browse files Browse the repository at this point in the history
…ape (#9805)

fix:bugprone-error

Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored Dec 27, 2024
1 parent 4d1f69d commit 8048b9e
Showing 1 changed file with 35 additions and 27 deletions.
62 changes: 35 additions & 27 deletions planning/autoware_static_centerline_generator/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,38 +14,46 @@

#include "static_centerline_generator_node.hpp"

#include <iostream>
#include <memory>
#include <string>

int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);

// initialize node
rclcpp::NodeOptions node_options;
auto node =
std::make_shared<autoware::static_centerline_generator::StaticCenterlineGeneratorNode>(
node_options);

// get ros parameter
const auto mode = node->declare_parameter<std::string>("mode");

// process
if (mode == "AUTO") {
node->generate_centerline();
node->validate();
node->save_map();
} else if (mode == "GUI") {
node->generate_centerline();
} else if (mode == "VMB") {
// Do nothing
} else {
throw std::invalid_argument("The `mode` is invalid.");
try {
rclcpp::init(argc, argv);

// initialize node
rclcpp::NodeOptions node_options;
auto node =
std::make_shared<autoware::static_centerline_generator::StaticCenterlineGeneratorNode>(
node_options);

// get ros parameter
const auto mode = node->declare_parameter<std::string>("mode");

// process
if (mode == "AUTO") {
node->generate_centerline();
node->validate();
node->save_map();
} else if (mode == "GUI") {
node->generate_centerline();
} else if (mode == "VMB") {
// Do nothing
} else {
throw std::invalid_argument("The `mode` is invalid.");
}

// NOTE: spin node to keep showing debug path/trajectory in rviz with transient local
rclcpp::spin(node);
rclcpp::shutdown();
} catch (const std::exception & e) {
std::cerr << "Exception in main(): " << e.what() << std::endl;
return {};
} catch (...) {
std::cerr << "Unknown exception in main()" << std::endl;
return {};
}

// NOTE: spin node to keep showing debug path/trajectory in rviz with transient local
rclcpp::spin(node);
rclcpp::shutdown();

return 0;
}

0 comments on commit 8048b9e

Please sign in to comment.