Skip to content

Commit

Permalink
Compile and fix samples (#27)
Browse files Browse the repository at this point in the history
* Add SBA and Eigen as dependencies
* Compile samples
  • Loading branch information
eborghi10 authored Sep 8, 2021
1 parent 6991694 commit 3ef9f6b
Show file tree
Hide file tree
Showing 7 changed files with 28 additions and 25 deletions.
11 changes: 9 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,16 @@
cmake_minimum_required(VERSION 3.0.2)
project(open_karto)

find_package(catkin REQUIRED)

find_package(catkin REQUIRED
COMPONENTS
sparse_bundle_adjustment
)
find_package(Eigen3 REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread)

catkin_package(
CATKIN_DEPENDS
sparse_bundle_adjustment
DEPENDS Boost
INCLUDE_DIRS
include
Expand All @@ -27,3 +32,5 @@ install(TARGETS karto
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
)

include(samples/CMakeLists.txt)
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,9 @@
<buildtool_depend>catkin</buildtool_depend>

<build_depend>boost</build_depend>
<build_depend>sparse_bundle_adjustment</build_depend>

<run_depend>boost</run_depend>
<run_depend>sparse_bundle_adjustment</run_depend>

</package>
22 changes: 8 additions & 14 deletions samples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,14 @@ if(WIN32)
endforeach(warning)
endif()

include_directories(../source)

############################################################################
# tutorial 1
add_executable(
Karto_Tutorial1
tutorial1.cpp
Karto_Tutorial1
samples/tutorial1.cpp
)

target_link_libraries(Karto_Tutorial1 OpenKarto)
target_link_libraries(Karto_Tutorial1 karto)

if (UNIX)
target_link_libraries(Karto_Tutorial1 "pthread")
Expand All @@ -46,20 +44,16 @@ endif()
############################################################################
# tutorial 2

include_directories(${CSPARSE_DIR}/CSparse/Include)
include_directories(${SBA_DIR}/sba/include)
include_directories(${EIGEN_DIR}/eigen)
include_directories(${EIGEN3_INCLUDE_DIRS})

add_executable(
Karto_Tutorial2
tutorial2.cpp
SpaSolver.h
SpaSolver.cpp
samples/tutorial2.cpp
samples/SpaSolver.h
samples/SpaSolver.cpp
)

target_link_libraries(Karto_Tutorial2 OpenKarto)
target_link_libraries(Karto_Tutorial2 spa2d)
target_link_libraries(Karto_Tutorial2 csparse)
target_link_libraries(Karto_Tutorial2 karto ${catkin_LIBRARIES} ${Eigen_LIBRARIES})

if(PNG_FOUND)
target_link_libraries(Karto_Tutorial2 ${ZLIB_LIBRARIES})
Expand Down
6 changes: 3 additions & 3 deletions samples/SpaSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
*/

#include "SpaSolver.h"
#include <OpenKarto/Karto.h>
#include <open_karto/Karto.h>

SpaSolver::SpaSolver()
{
Expand Down Expand Up @@ -59,7 +59,7 @@ void SpaSolver::AddNode(karto::Vertex<karto::LocalizedRangeScan>* pVertex)
{
karto::Pose2 pose = pVertex->GetObject()->GetCorrectedPose();
Eigen::Vector3d vector(pose.GetX(), pose.GetY(), pose.GetHeading());
m_Spa.addNode2d(vector, pVertex->GetObject()->GetUniqueId());
m_Spa.addNode(vector, pVertex->GetObject()->GetUniqueId());
}

void SpaSolver::AddConstraint(karto::Edge<karto::LocalizedRangeScan>* pEdge)
Expand All @@ -80,5 +80,5 @@ void SpaSolver::AddConstraint(karto::Edge<karto::LocalizedRangeScan>* pEdge)
m(1,2) = m(2,1) = precisionMatrix(1,2);
m(2,2) = precisionMatrix(2,2);

m_Spa.addConstraint2d(pSource->GetUniqueId(), pTarget->GetUniqueId(), mean, m);
m_Spa.addConstraint(pSource->GetUniqueId(), pTarget->GetUniqueId(), mean, m);
}
4 changes: 2 additions & 2 deletions samples/SpaSolver.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#ifndef __SPASOLVER__
#define __SPASOLVER__

#include <OpenKarto/Mapper.h>
#include <open_karto/Mapper.h>

#ifndef EIGEN_USE_NEW_STDVECTOR
#define EIGEN_USE_NEW_STDVECTOR
Expand All @@ -27,7 +27,7 @@
#define EIGEN_DEFAULT_IO_FORMAT Eigen::IOFormat(10)
#include <Eigen/Eigen>

#include "sba/spa2d.h"
#include "sparse_bundle_adjustment/spa2d.h"

typedef std::vector<karto::Matrix3> CovarianceVector;

Expand Down
4 changes: 2 additions & 2 deletions samples/tutorial1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include <OpenKarto/Mapper.h>
#include <open_karto/Mapper.h>

/**
* Sample code to demonstrate karto map creation
Expand Down Expand Up @@ -146,7 +146,7 @@ void PrintOccupancyGrid(karto::OccupancyGrid* pOccupancyGrid)
}
}

int main(int /*argc*/, char /***argv*/)
int main(int /*argc*/, char **/*argv*/)
{
// use try/catch to catch karto exceptions that might be thrown by the karto subsystem.
/////////////////////////////////////
Expand Down
4 changes: 2 additions & 2 deletions samples/tutorial2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "SpaSolver.h"

#include <OpenKarto/Mapper.h>
#include <open_karto/Mapper.h>

/**
* Sample code to demonstrate karto map creation
Expand Down Expand Up @@ -148,7 +148,7 @@ void PrintOccupancyGrid(karto::OccupancyGrid* pOccupancyGrid)
}
}

int main(int /*argc*/, char /***argv*/)
int main(int /*argc*/, char **/*argv*/)
{
// use try/catch to catch karto exceptions that might be thrown by the karto subsystem.
/////////////////////////////////////
Expand Down

0 comments on commit 3ef9f6b

Please sign in to comment.