80 lines
2.2 KiB
Diff
80 lines
2.2 KiB
Diff
From abae137977a7177704343d81814e863070986ab5 Mon Sep 17 00:00:00 2001
|
|
From: Alberto Soragna <alberto.soragna@gmail.com>
|
|
Date: Thu, 7 Mar 2019 20:47:48 +0000
|
|
Subject: removed bullet dependency from map_server (#594)
|
|
|
|
---
|
|
CMakeLists.txt | 3 ---
|
|
package.xml | 1 -
|
|
src/occ_grid_loader.cpp | 7 +++----
|
|
3 files changed, 3 insertions(+), 8 deletions(-)
|
|
|
|
diff --git a/CMakeLists.txt b/CMakeLists.txt
|
|
index cd7724a..bed6272 100644
|
|
--- a/CMakeLists.txt
|
|
+++ b/CMakeLists.txt
|
|
@@ -5,7 +5,6 @@ find_package(ament_cmake REQUIRED)
|
|
find_package(nav2_common REQUIRED)
|
|
find_package(rclcpp REQUIRED)
|
|
find_package(nav_msgs REQUIRED)
|
|
-find_package(Bullet REQUIRED)
|
|
find_package(SDL REQUIRED)
|
|
find_package(SDL_image REQUIRED)
|
|
find_package(yaml_cpp_vendor REQUIRED)
|
|
@@ -16,7 +15,6 @@ nav2_package()
|
|
|
|
include_directories(
|
|
include
|
|
- ${BULLET_INCLUDE_DIRS}
|
|
${SDL_INCLUDE_DIR}
|
|
${SDL_IMAGE_INCLUDE_DIRS}
|
|
)
|
|
@@ -76,7 +74,6 @@ target_link_libraries(${map_saver_executable}
|
|
)
|
|
|
|
target_link_libraries(${library_name}
|
|
- ${BULLET_LIBRARIES}
|
|
${SDL_LIBRARY}
|
|
${SDL_IMAGE_LIBRARIES}
|
|
)
|
|
diff --git a/package.xml b/package.xml
|
|
index 107c0d7..8a65c81 100644
|
|
--- a/package.xml
|
|
+++ b/package.xml
|
|
@@ -12,7 +12,6 @@
|
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
|
<build_depend>nav2_common</build_depend>
|
|
|
|
- <depend>bullet</depend>
|
|
<depend>nav_msgs</depend>
|
|
<depend>std_msgs</depend>
|
|
<depend>rclcpp</depend>
|
|
diff --git a/src/occ_grid_loader.cpp b/src/occ_grid_loader.cpp
|
|
index 76b43b2..ae32b63 100644
|
|
--- a/src/occ_grid_loader.cpp
|
|
+++ b/src/occ_grid_loader.cpp
|
|
@@ -39,7 +39,7 @@
|
|
#include <memory>
|
|
#include <stdexcept>
|
|
|
|
-#include "LinearMath/btQuaternion.h"
|
|
+#include "tf2/LinearMath/Quaternion.h"
|
|
#include "SDL/SDL_image.h"
|
|
|
|
using namespace std::chrono_literals;
|
|
@@ -136,9 +136,8 @@ void OccGridLoader::loadMapFromFile(const std::string & map_name)
|
|
msg_.info.origin.position.x = origin_[0];
|
|
msg_.info.origin.position.y = origin_[1];
|
|
msg_.info.origin.position.z = 0.0;
|
|
- btQuaternion q;
|
|
- // setEulerZYX(yaw, pitch, roll)
|
|
- q.setEulerZYX(origin_[2], 0, 0);
|
|
+ tf2::Quaternion q;
|
|
+ q.setRPY(0, 0, origin_[2]);
|
|
msg_.info.origin.orientation.x = q.x();
|
|
msg_.info.origin.orientation.y = q.y();
|
|
msg_.info.origin.orientation.z = q.z();
|
|
--
|
|
2.17.1
|
|
|