add example that does not need ROS support
parent
1fec0404bb
commit
78504c1b9a
21
README.md
21
README.md
|
@ -27,17 +27,32 @@ Although **Oh-My-LOAM** is ROS-free, running it with ROS bag as input is the sim
|
||||||
We'll take *nsh_indoor_outdoor.bag* as example.
|
We'll take *nsh_indoor_outdoor.bag* as example.
|
||||||
You can download this bag from [google drive](https://drive.google.com/file/d/1s05tBQOLNEDDurlg48KiUWxCp-YqYyGH/view) or [baidupan](https://pan.baidu.com/s/1TbfMQ3Rvmmn1hCjFhXSPcQ) (提取码:9nf7).
|
You can download this bag from [google drive](https://drive.google.com/file/d/1s05tBQOLNEDDurlg48KiUWxCp-YqYyGH/view) or [baidupan](https://pan.baidu.com/s/1TbfMQ3Rvmmn1hCjFhXSPcQ) (提取码:9nf7).
|
||||||
|
|
||||||
Launch:
|
Launch **Oh-My-LOAM**:
|
||||||
```
|
```
|
||||||
./devel/lib/oh_my_loam/main_rosbag ../configs/config_nsh_indoor_outdoor.yaml
|
./devel/lib/oh_my_loam/main_rosbag ../configs/config_nsh_indoor_outdoor.yaml
|
||||||
```
|
```
|
||||||
Play bag:
|
Play ROS bag (in a new terminal):
|
||||||
```
|
```
|
||||||
ros play nsh_indoor_outdoor.bag
|
ros play nsh_indoor_outdoor.bag
|
||||||
```
|
```
|
||||||
|
|
||||||
## Run without ROS support
|
## Run without ROS support
|
||||||
You can write by yourself.
|
Launch **Oh-My-LOAM**:
|
||||||
|
```
|
||||||
|
./devel/lib/oh_my_loam/main_noros ../configs/config_nsh_indoor_outdoor.yaml xxxxxx
|
||||||
|
```
|
||||||
|
Please replace `xxxxxx` with the directory that contains the input point cloud files with tree structure like following:
|
||||||
|
```
|
||||||
|
xxxxxx
|
||||||
|
├── frame00000.pcd
|
||||||
|
├── frame00001.pcd
|
||||||
|
├── frame00002.pcd
|
||||||
|
├── frame00003.pcd
|
||||||
|
├── frame00004.pcd
|
||||||
|
├── ...
|
||||||
|
```
|
||||||
|
Currently only `.pcd` format is supported.
|
||||||
|
You can modify `examples/main_noros.cc` to add support for other point cloud formats.
|
||||||
|
|
||||||
# Dependences
|
# Dependences
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,13 @@
|
||||||
|
|
||||||
|
#include "common/config/yaml_config.h"
|
||||||
|
|
||||||
|
namespace common {
|
||||||
|
|
||||||
|
YAMLConfig::YAMLConfig() {}
|
||||||
|
|
||||||
|
void YAMLConfig::Init(const std::string &file) {
|
||||||
|
config_.reset(new YAML::Node);
|
||||||
|
*config_ = YAML::LoadFile(file);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace common
|
|
@ -11,10 +11,7 @@ namespace common {
|
||||||
|
|
||||||
class YAMLConfig {
|
class YAMLConfig {
|
||||||
public:
|
public:
|
||||||
void Init(const std::string &file) {
|
void Init(const std::string &file);
|
||||||
config_.reset(new YAML::Node);
|
|
||||||
*config_ = YAML::LoadFile(file);
|
|
||||||
}
|
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
const T Get(const std::string &key) const {
|
const T Get(const std::string &key) const {
|
||||||
|
|
|
@ -68,7 +68,7 @@ std::string CustomSink::GetColorCode(const LEVELS &level) const {
|
||||||
return "\033[1m\033[34m"; // bold blue
|
return "\033[1m\033[34m"; // bold blue
|
||||||
}
|
}
|
||||||
if (g3::internal::wasFatal(level)) {
|
if (g3::internal::wasFatal(level)) {
|
||||||
return "\033[1m\033[31m"; // red
|
return "\033[1m\033[31m"; // bold red
|
||||||
}
|
}
|
||||||
return "\033[97m"; // white
|
return "\033[97m"; // white
|
||||||
}
|
}
|
||||||
|
|
|
@ -20,5 +20,5 @@
|
||||||
} \
|
} \
|
||||||
\
|
\
|
||||||
private: \
|
private: \
|
||||||
classname() = default; \
|
classname(); \
|
||||||
DISALLOW_COPY_AND_ASSIGN(classname)
|
DISALLOW_COPY_AND_ASSIGN(classname)
|
||||||
|
|
|
@ -32,3 +32,19 @@ target_link_libraries(main_rosbag
|
||||||
visualizer
|
visualizer
|
||||||
base
|
base
|
||||||
)
|
)
|
||||||
|
|
||||||
|
add_executable(main_noros main_noros.cc)
|
||||||
|
target_link_libraries(main_noros
|
||||||
|
${PCL_LIBRARIES}
|
||||||
|
${G3LOG_LIBRARIES}
|
||||||
|
${YAML_CPP_LIBRARIES}
|
||||||
|
common
|
||||||
|
oh_my_loam
|
||||||
|
extractor
|
||||||
|
odometer
|
||||||
|
mapper
|
||||||
|
solver
|
||||||
|
${CERES_LIBRARIES}
|
||||||
|
visualizer
|
||||||
|
base
|
||||||
|
)
|
|
@ -0,0 +1,67 @@
|
||||||
|
#include <pcl/io/pcd_io.h>
|
||||||
|
|
||||||
|
#include <chrono>
|
||||||
|
#include <filesystem>
|
||||||
|
#include <functional>
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
#include "common/common.h"
|
||||||
|
#include "oh_my_loam/oh_my_loam.h"
|
||||||
|
|
||||||
|
using namespace common;
|
||||||
|
using namespace oh_my_loam;
|
||||||
|
namespace fs = std::filesystem;
|
||||||
|
|
||||||
|
void PointCloudHandler(const PointCloudConstPtr &cloud, OhMyLoam *const slam);
|
||||||
|
|
||||||
|
int main(int argc, char *argv[]) {
|
||||||
|
if (argc != 3) {
|
||||||
|
std::cerr << "\033[1m\033[31mConfiguration file and input path should be "
|
||||||
|
"specified!\033[m"
|
||||||
|
<< std::endl;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
// config
|
||||||
|
YAMLConfig::Instance()->Init(argv[1]);
|
||||||
|
bool is_log_to_file = YAMLConfig::Instance()->Get<bool>("log_to_file");
|
||||||
|
std::string log_path = YAMLConfig::Instance()->Get<std::string>("log_path");
|
||||||
|
std::string lidar = YAMLConfig::Instance()->Get<std::string>("lidar");
|
||||||
|
// logging
|
||||||
|
InitG3Logging(is_log_to_file, "oh_my_loam_" + lidar, log_path);
|
||||||
|
AUSER << "LOAM start..., lidar = " << lidar;
|
||||||
|
// SLAM system
|
||||||
|
OhMyLoam slam;
|
||||||
|
if (!slam.Init()) {
|
||||||
|
AFATAL << "Failed to initilize slam system.";
|
||||||
|
}
|
||||||
|
// get input point cloud file names
|
||||||
|
ACHECK(fs::exists(argv[2])) << "Directory not exist: " << argv[2];
|
||||||
|
std::vector<fs::path> cloud_paths;
|
||||||
|
for (auto &it : fs::directory_iterator(argv[2])) {
|
||||||
|
if (fs::is_regular_file(it.path())) cloud_paths.push_back(it.path());
|
||||||
|
}
|
||||||
|
AWARN_IF(cloud_paths.empty())
|
||||||
|
<< "No point cloud file in directory: " << argv[2];
|
||||||
|
AINFO_IF(!cloud_paths.empty())
|
||||||
|
<< "There are " << cloud_paths.size() << " point clouds in total";
|
||||||
|
std::sort(cloud_paths.begin(), cloud_paths.end());
|
||||||
|
// load point cloud and process
|
||||||
|
for (auto &path : cloud_paths) {
|
||||||
|
PointCloudPtr cloud(new PointCloud);
|
||||||
|
pcl::io::loadPCDFile(path.string(), *cloud);
|
||||||
|
PointCloudHandler(cloud, &slam);
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void PointCloudHandler(const PointCloudConstPtr &cloud, OhMyLoam *const slam) {
|
||||||
|
auto millisecs = std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||||
|
std::chrono::system_clock::now().time_since_epoch());
|
||||||
|
double timestamp = millisecs.count() / 1000.0;
|
||||||
|
static size_t frame_id = 0;
|
||||||
|
AINFO << "Ohmyloam: frame_id = " << ++frame_id
|
||||||
|
<< ", timestamp = " << FMT_TIMESTAMP(timestamp)
|
||||||
|
<< ", point_number = " << cloud->size();
|
||||||
|
slam->Run(timestamp, cloud);
|
||||||
|
}
|
|
@ -16,13 +16,18 @@ void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr &msg,
|
||||||
OhMyLoam *const slam);
|
OhMyLoam *const slam);
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
|
if (argc != 2) {
|
||||||
|
std::cerr << "\033[1m\033[31mConfiguration file should be specified!\033[m"
|
||||||
|
<< std::endl;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
// config
|
// config
|
||||||
YAMLConfig::Instance()->Init(argv[1]);
|
YAMLConfig::Instance()->Init(argv[1]);
|
||||||
bool log_to_file = YAMLConfig::Instance()->Get<bool>("log_to_file");
|
bool is_log_to_file = YAMLConfig::Instance()->Get<bool>("log_to_file");
|
||||||
std::string log_path = YAMLConfig::Instance()->Get<std::string>("log_path");
|
std::string log_path = YAMLConfig::Instance()->Get<std::string>("log_path");
|
||||||
std::string lidar = YAMLConfig::Instance()->Get<std::string>("lidar");
|
std::string lidar = YAMLConfig::Instance()->Get<std::string>("lidar");
|
||||||
// logging
|
// logging
|
||||||
InitG3Logging(log_to_file, "oh_my_loam_" + lidar, log_path);
|
InitG3Logging(is_log_to_file, "oh_my_loam_" + lidar, log_path);
|
||||||
AUSER << "LOAM start..., lidar = " << lidar;
|
AUSER << "LOAM start..., lidar = " << lidar;
|
||||||
// SLAM system
|
// SLAM system
|
||||||
OhMyLoam slam;
|
OhMyLoam slam;
|
||||||
|
|
Loading…
Reference in New Issue