-
Notifications
You must be signed in to change notification settings - Fork 25
/
sm-cli-join.cpp
67 lines (51 loc) · 1.96 KB
/
sm-cli-join.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
/*+-------------------------------------------------------------------------+
| MultiVehicle simulator (libmvsim) |
| |
| Copyright (C) 2014-2023 Jose Luis Blanco Claraco |
| Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) |
| Distributed under 3-clause BSD License |
| See COPYING |
+-------------------------------------------------------------------------+ */
#include <mrpt/core/exceptions.h>
#include <mrpt/maps/CSimpleMap.h>
#include "sm-cli.h"
static int printCommandsJoin(bool showErrorMsg);
int commandJoin()
{
const auto& lstCmds = cli->argCmd.getValue();
if (cli->argHelp.isSet()) return printCommandsJoin(false);
if (lstCmds.size() < 2 || !cli->arg_output.isSet())
return printCommandsJoin(true);
// Take second unlabeled argument:
mrpt::maps::CSimpleMap outSM;
for (size_t i = 1; i < lstCmds.size(); i++)
{
const std::string file = lstCmds.at(i);
mrpt::maps::CSimpleMap sm = read_input_sm_from_cli(file);
for (size_t k = 0; k < sm.size(); k++)
{
const auto kf = sm.get(k);
outSM.insert(kf);
}
}
const auto outFil = cli->arg_output.getValue();
std::cout << "Writing merged simplemap with " << outSM.size()
<< " keyframes to '" << outFil << "'" << std::endl;
outSM.saveToFile(outFil);
return 0;
}
int printCommandsJoin(bool showErrorMsg)
{
if (showErrorMsg)
{
setConsoleErrorColor();
std::cerr << "Error: missing or unknown subcommand.\n";
setConsoleNormalColor();
}
fprintf(
stderr,
R"XXX(Usage:
sm-cli join <filename_1> [<filename_2> ...] --output <MERGED.simplemap>
)XXX");
return showErrorMsg ? 1 : 0;
}