DRAFT nav2-map-server-0.1.7.inc: Fix compile error
This commit is contained in:
parent
6459053e3b
commit
d996762c63
|
@ -8,4 +8,5 @@ FILESEXTRAPATHS_prepend := "${THISDIR}/nav2-map-server:"
|
|||
|
||||
SRC_URI += " \
|
||||
file://0001-removed-bullet-dependency-from-map_server-594.patch \
|
||||
file://0002-Fix-build-with-catching-polymorphic-type-error.patch \
|
||||
"
|
||||
|
|
|
@ -0,0 +1,80 @@
|
|||
From 061dd9f0ca8b67ea6ccd8c692d69f1c4c5aa7e80 Mon Sep 17 00:00:00 2001
|
||||
From: JeongBong Seo <jb.seo@lge.com>
|
||||
Date: Mon, 22 Apr 2019 11:25:51 +0900
|
||||
Subject: Fix build with catching polymorphic type error
|
||||
|
||||
---
|
||||
src/map_server.cpp | 4 ++--
|
||||
src/occ_grid_loader.cpp | 10 +++++-----
|
||||
2 files changed, 7 insertions(+), 7 deletions(-)
|
||||
|
||||
diff --git a/src/map_server.cpp b/src/map_server.cpp
|
||||
index 61e483e..86aae6d 100644
|
||||
--- a/src/map_server.cpp
|
||||
+++ b/src/map_server.cpp
|
||||
@@ -75,7 +75,7 @@ void MapServer::getParameters()
|
||||
map_filename_ = std::string(dirname(fname_copy)) + '/' + map_filename_;
|
||||
free(fname_copy);
|
||||
}
|
||||
- } catch (YAML::Exception) {
|
||||
+ } catch (YAML::Exception &) {
|
||||
std::string msg = "'" + yaml_filename_ + "' does not contain an image tag or it is invalid";
|
||||
throw std::runtime_error(msg);
|
||||
}
|
||||
@@ -83,7 +83,7 @@ void MapServer::getParameters()
|
||||
// Get the map type so that we can create the correct map loader
|
||||
try {
|
||||
map_type_ = doc_["map_type"].as<std::string>();
|
||||
- } catch (YAML::Exception) {
|
||||
+ } catch (YAML::Exception &) {
|
||||
// Default to occupancy grid if not specified in the YAML file
|
||||
map_type_ = "occupancy";
|
||||
}
|
||||
diff --git a/src/occ_grid_loader.cpp b/src/occ_grid_loader.cpp
|
||||
index ae32b63..aa72fa7 100644
|
||||
--- a/src/occ_grid_loader.cpp
|
||||
+++ b/src/occ_grid_loader.cpp
|
||||
@@ -56,7 +56,7 @@ OccGridLoader::OccGridLoader(rclcpp::Node * node, YAML::Node & doc)
|
||||
{
|
||||
try {
|
||||
resolution_ = doc_["resolution"].as<double>();
|
||||
- } catch (YAML::Exception) {
|
||||
+ } catch (YAML::Exception &) {
|
||||
throw std::runtime_error("The map does not contain a resolution tag or it is invalid");
|
||||
}
|
||||
|
||||
@@ -64,19 +64,19 @@ OccGridLoader::OccGridLoader(rclcpp::Node * node, YAML::Node & doc)
|
||||
origin_[0] = doc_["origin"][0].as<double>();
|
||||
origin_[1] = doc_["origin"][1].as<double>();
|
||||
origin_[2] = doc_["origin"][2].as<double>();
|
||||
- } catch (YAML::Exception) {
|
||||
+ } catch (YAML::Exception &) {
|
||||
throw std::runtime_error("The map does not contain an origin tag or it is invalid");
|
||||
}
|
||||
|
||||
try {
|
||||
free_thresh_ = doc_["free_thresh"].as<double>();
|
||||
- } catch (YAML::Exception) {
|
||||
+ } catch (YAML::Exception &) {
|
||||
throw std::runtime_error("The map does not contain a free_thresh tag or it is invalid");
|
||||
}
|
||||
|
||||
try {
|
||||
occupied_thresh_ = doc_["occupied_thresh"].as<double>();
|
||||
- } catch (YAML::Exception) {
|
||||
+ } catch (YAML::Exception &) {
|
||||
throw std::runtime_error("The map does not contain an occupied_thresh tag or it is invalid");
|
||||
}
|
||||
|
||||
@@ -104,7 +104,7 @@ OccGridLoader::OccGridLoader(rclcpp::Node * node, YAML::Node & doc)
|
||||
|
||||
try {
|
||||
negate_ = doc_["negate"].as<int>();
|
||||
- } catch (YAML::Exception) {
|
||||
+ } catch (YAML::Exception &) {
|
||||
throw std::runtime_error("The map does not contain a negate tag or it is invalid");
|
||||
}
|
||||
|
||||
--
|
||||
2.17.1
|
||||
|
Loading…
Reference in New Issue