Remove custom SIGINT handler from offline node. (#470)
parent
63aba81e31
commit
2042b73010
|
@ -16,7 +16,6 @@
|
|||
|
||||
#include <time.h>
|
||||
#include <chrono>
|
||||
#include <csignal>
|
||||
#include <sstream>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
@ -62,10 +61,6 @@ constexpr char kClockTopic[] = "clock";
|
|||
constexpr char kTfStaticTopic[] = "/tf_static";
|
||||
constexpr char kTfTopic[] = "tf";
|
||||
|
||||
volatile std::sig_atomic_t sigint_triggered = 0;
|
||||
|
||||
void SigintHandler(int) { sigint_triggered = 1; }
|
||||
|
||||
// TODO(hrapp): This is duplicated in node_main.cc. Pull out into a config
|
||||
// unit.
|
||||
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions() {
|
||||
|
@ -130,7 +125,7 @@ void Run(const std::vector<string>& bag_filenames) {
|
|||
}
|
||||
|
||||
for (const string& bag_filename : bag_filenames) {
|
||||
if (sigint_triggered) {
|
||||
if (!::ros::ok()) {
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -148,7 +143,7 @@ void Run(const std::vector<string>& bag_filenames) {
|
|||
// because it gets very inefficient with a large one.
|
||||
std::deque<rosbag::MessageInstance> delayed_messages;
|
||||
for (const rosbag::MessageInstance& msg : view) {
|
||||
if (sigint_triggered) {
|
||||
if (!::ros::ok()) {
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -252,9 +247,7 @@ int main(int argc, char** argv) {
|
|||
<< "-configuration_basename is missing.";
|
||||
CHECK(!FLAGS_bag_filenames.empty()) << "-bag_filenames is missing.";
|
||||
|
||||
std::signal(SIGINT, &::cartographer_ros::SigintHandler);
|
||||
::ros::init(argc, argv, "cartographer_offline_node",
|
||||
::ros::init_options::NoSigintHandler);
|
||||
::ros::init(argc, argv, "cartographer_offline_node");
|
||||
::ros::start();
|
||||
|
||||
cartographer_ros::ScopedRosLogSink ros_log_sink;
|
||||
|
|
Loading…
Reference in New Issue