Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adapt package for a successful compilation in Ubuntu 18.04 and ROS Melodic #354

Open
wants to merge 1 commit into
base: catkin
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 13 additions & 6 deletions lsd_slam_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,11 @@ find_package(catkin REQUIRED COMPONENTS
image_transport
roscpp
rosbag
cmake_modules
lsd_slam_msgs
)

find_package(OpenCV REQUIRED)
find_package(Eigen REQUIRED)
find_package(X11 REQUIRED)
include(cmake/FindG2O.cmake)
Expand All @@ -42,7 +45,7 @@ generate_dynamic_reconfigure_options(
catkin_package(
LIBRARIES lsdslam
DEPENDS Eigen SuiteSparse
CATKIN_DEPENDS libg2o
CATKIN_DEPENDS libg2o
)

# SSE flags
Expand Down Expand Up @@ -87,28 +90,32 @@ set(SOURCE_FILES

include_directories(
include
${EIGEN3_INCLUDE_DIR}
${EIGEN_INCLUDE_DIR}
${PROJECT_SOURCE_DIR}/src
${PROJECT_SOURCE_DIR}/thirdparty/Sophus
${CSPARSE_INCLUDE_DIR} #Has been set by SuiteParse
${CHOLMOD_INCLUDE_DIR} #Has been set by SuiteParse
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)


# build shared library.
add_library(lsdslam SHARED ${SOURCE_FILES})
target_link_libraries(lsdslam ${FABMAP_LIB} ${G2O_LIBRARIES} ${catkin_LIBRARIES} csparse cxsparse )
add_dependencies(lsdslam ${catkin_EXPORTED_TARGETS})
target_link_libraries(lsdslam ${FABMAP_LIB} ${G2O_LIBRARIES} ${catkin_LIBRARIES} cxsparse X11)
#rosbuild_link_boost(lsdslam thread)


# build live ros node
add_executable(live_slam src/main_live_odometry.cpp)
target_link_libraries(live_slam lsdslam ${catkin_LIBRARIES} ${G2O_LIBRARIES})
add_dependencies(live_slam ${catkin_EXPORTED_TARGETS})
target_link_libraries(live_slam lsdslam ${catkin_LIBRARIES} ${G2O_LIBRARIES} ${OpenCV_LIBRARIES})


# build image node
add_executable(dataset src/main_on_images.cpp)
target_link_libraries(dataset lsdslam ${catkin_LIBRARIES} ${G2O_LIBRARIES})
add_dependencies(dataset ${catkin_EXPORTED_TARGETS})
target_link_libraries(dataset lsdslam ${catkin_LIBRARIES} ${G2O_LIBRARIES} ${OpenCV_LIBRARIES})

# TODO add INSTALL

Expand Down
8 changes: 5 additions & 3 deletions lsd_slam_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,20 +16,22 @@
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>lsd_slam_viewer</build_depend>
<build_depend>lsd_slam_msgs</build_depend>
<build_depend>rosbag</build_depend>
<build_depend>eigen</build_depend>
<build_depend>suitesparse</build_depend>
<build_depend>libg2o</build_depend>
<build_depend>cmake_modules</build_depend>

<run_depend>cv_bridge</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>lsd_slam_viewer</run_depend>
<run_depend>lsd_slam_msgs</run_depend>
<run_depend>rosbag</run_depend>
<run_depend>eigen</run_depend>
<run_depend>suitesparse</run_depend>
<run_depend>libg2o</run_depend>

<run_depend>cmake_modules</run_depend>

</package>
8 changes: 4 additions & 4 deletions lsd_slam_core/src/DepthEstimation/DepthMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1111,13 +1111,13 @@ void DepthMap::updateKeyframe(std::deque< std::shared_ptr<Frame> > referenceFram
{
cv::Mat keyFrameImage(activeKeyFrame->height(), activeKeyFrame->width(), CV_32F, const_cast<float*>(activeKeyFrameImageData));
keyFrameImage.convertTo(debugImageHypothesisHandling, CV_8UC1);
cv::cvtColor(debugImageHypothesisHandling, debugImageHypothesisHandling, CV_GRAY2RGB);
cv::cvtColor(debugImageHypothesisHandling, debugImageHypothesisHandling, cv::COLOR_GRAY2RGB);

cv::Mat oldest_refImage(oldest_referenceFrame->height(), oldest_referenceFrame->width(), CV_32F, const_cast<float*>(oldest_referenceFrame->image(0)));
cv::Mat newest_refImage(newest_referenceFrame->height(), newest_referenceFrame->width(), CV_32F, const_cast<float*>(newest_referenceFrame->image(0)));
cv::Mat rfimg = 0.5f*oldest_refImage + 0.5f*newest_refImage;
rfimg.convertTo(debugImageStereoLines, CV_8UC1);
cv::cvtColor(debugImageStereoLines, debugImageStereoLines, CV_GRAY2RGB);
cv::cvtColor(debugImageStereoLines, debugImageStereoLines, cv::COLOR_GRAY2RGB);
}

struct timeval tv_start, tv_end;
Expand Down Expand Up @@ -1238,7 +1238,7 @@ void DepthMap::createKeyFrame(Frame* new_keyframe)
{
cv::Mat keyFrameImage(new_keyframe->height(), new_keyframe->width(), CV_32F, const_cast<float*>(new_keyframe->image(0)));
keyFrameImage.convertTo(debugImageHypothesisPropagation, CV_8UC1);
cv::cvtColor(debugImageHypothesisPropagation, debugImageHypothesisPropagation, CV_GRAY2RGB);
cv::cvtColor(debugImageHypothesisPropagation, debugImageHypothesisPropagation, cv::COLOR_GRAY2RGB);
}


Expand Down Expand Up @@ -1403,7 +1403,7 @@ int DepthMap::debugPlotDepthMap()

cv::Mat keyFrameImage(activeKeyFrame->height(), activeKeyFrame->width(), CV_32F, const_cast<float*>(activeKeyFrameImageData));
keyFrameImage.convertTo(debugImageDepth, CV_8UC1);
cv::cvtColor(debugImageDepth, debugImageDepth, CV_GRAY2RGB);
cv::cvtColor(debugImageDepth, debugImageDepth, cv::COLOR_GRAY2RGB);

// debug plot & publish sparse version?
int refID = referenceFrameByID_offset;
Expand Down
2 changes: 1 addition & 1 deletion lsd_slam_core/src/GlobalMapping/FabMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ void FabMap::compareAndAdd(Frame* keyframe, int* out_newID, int* out_loopID)
cv::Mat frame;
cv::Mat keyFrameImage(keyframe->height(), keyframe->width(), CV_32F, const_cast<float*>(keyframe->image()));
keyFrameImage.convertTo(frame, CV_8UC1);
//cv::cvtColor(frame, frame, CV_GRAY2RGB);
//cv::cvtColor(frame, frame, cv::COLOR_GRAY2RGB);

// Generate FabMap bag-of-words data (image descriptor)
cv::Mat bow;
Expand Down
6 changes: 4 additions & 2 deletions lsd_slam_core/src/GlobalMapping/KeyFrameGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,10 @@ KeyFrameGraph::KeyFrameGraph()
typedef g2o::LinearSolverCSparse<BlockSolver::PoseMatrixType> LinearSolver;
//typedef g2o::LinearSolverPCG<BlockSolver::PoseMatrixType> LinearSolver;
LinearSolver* solver = new LinearSolver();
BlockSolver* blockSolver = new BlockSolver(solver);
g2o::OptimizationAlgorithmLevenberg* algorithm = new g2o::OptimizationAlgorithmLevenberg(blockSolver);
// BlockSolver* blockSolver = new BlockSolver(solver);
BlockSolver* blockSolver = new BlockSolver(std::unique_ptr<LinearSolver>(solver));
// g2o::OptimizationAlgorithmLevenberg* algorithm = new g2o::OptimizationAlgorithmLevenberg(blockSolver);
g2o::OptimizationAlgorithmLevenberg* algorithm = new g2o::OptimizationAlgorithmLevenberg(std::unique_ptr<BlockSolver>(blockSolver));
graph.setAlgorithm(algorithm);

graph.setVerbose(false); // printOptimizationInfo
Expand Down
2 changes: 1 addition & 1 deletion lsd_slam_core/src/GlobalMapping/g2oTypeSim3Sophus.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ class EdgeSim3 : public g2o::BaseBinaryEdge<7, Sophus::Sim3d, VertexSim3, Vertex

virtual bool setMeasurementData(const double* m)
{
Eigen::Map<const g2o::Vector7d> v(m);
Eigen::Map<const Eigen::Matrix<double, 7 ,1> > v(m);
setMeasurement(Sophus::Sim3d::exp(v));
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion lsd_slam_core/src/IOWrapper/ImageDisplay.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ inline void displayImage(const char* windowName, const float* image, int width,
cv::Mat floatWrapper(height, width, CV_32F, const_cast<float*>(image));
cv::Mat tempImage(height, width, CV_8UC1);
floatWrapper.convertTo(tempImage, CV_8UC1);
cv::cvtColor(tempImage, tempImage, CV_GRAY2RGB);
cv::cvtColor(tempImage, tempImage, cv::COLOR_GRAY2RGB);
displayImage(windowName, tempImage);
}

Expand Down
16 changes: 8 additions & 8 deletions lsd_slam_core/src/IOWrapper/ROS/ROSOutput3DWrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@


#include "std_msgs/Float32MultiArray.h"
#include "lsd_slam_viewer/keyframeGraphMsg.h"
#include "lsd_slam_viewer/keyframeMsg.h"
#include "lsd_slam_msgs/keyframeGraphMsg.h"
#include "lsd_slam_msgs/keyframeMsg.h"

#include "DataStructures/Frame.h"
#include "GlobalMapping/KeyFrameGraph.h"
Expand All @@ -44,13 +44,13 @@ ROSOutput3DWrapper::ROSOutput3DWrapper(int width, int height)
this->height = height;

liveframe_channel = nh_.resolveName("lsd_slam/liveframes");
liveframe_publisher = nh_.advertise<lsd_slam_viewer::keyframeMsg>(liveframe_channel,1);
liveframe_publisher = nh_.advertise<lsd_slam_msgs::keyframeMsg>(liveframe_channel,1);

keyframe_channel = nh_.resolveName("lsd_slam/keyframes");
keyframe_publisher = nh_.advertise<lsd_slam_viewer::keyframeMsg>(keyframe_channel,1);
keyframe_publisher = nh_.advertise<lsd_slam_msgs::keyframeMsg>(keyframe_channel,1);

graph_channel = nh_.resolveName("lsd_slam/graph");
graph_publisher = nh_.advertise<lsd_slam_viewer::keyframeGraphMsg>(graph_channel,1);
graph_publisher = nh_.advertise<lsd_slam_msgs::keyframeGraphMsg>(graph_channel,1);

debugInfo_channel = nh_.resolveName("lsd_slam/debug");
debugInfo_publisher = nh_.advertise<std_msgs::Float32MultiArray>(debugInfo_channel,1);
Expand All @@ -69,7 +69,7 @@ ROSOutput3DWrapper::~ROSOutput3DWrapper()

void ROSOutput3DWrapper::publishKeyframe(Frame* f)
{
lsd_slam_viewer::keyframeMsg fMsg;
lsd_slam_msgs::keyframeMsg fMsg;


boost::shared_lock<boost::shared_mutex> lock = f->getActiveLock();
Expand Down Expand Up @@ -113,7 +113,7 @@ void ROSOutput3DWrapper::publishKeyframe(Frame* f)

void ROSOutput3DWrapper::publishTrackedFrame(Frame* kf)
{
lsd_slam_viewer::keyframeMsg fMsg;
lsd_slam_msgs::keyframeMsg fMsg;


fMsg.id = kf->id();
Expand Down Expand Up @@ -163,7 +163,7 @@ void ROSOutput3DWrapper::publishTrackedFrame(Frame* kf)

void ROSOutput3DWrapper::publishKeyframeGraph(KeyFrameGraph* graph)
{
lsd_slam_viewer::keyframeGraphMsg gMsg;
lsd_slam_msgs::keyframeGraphMsg gMsg;

graph->edgesListsMutex.lock();
gMsg.numConstraints = graph->edgesAll.size();
Expand Down
2 changes: 1 addition & 1 deletion lsd_slam_core/src/LiveSLAMWrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ void LiveSLAMWrapper::newImageCallback(const cv::Mat& img, Timestamp imgTime)
if (img.channels() == 1)
grayImg = img;
else
cvtColor(img, grayImg, CV_RGB2GRAY);
cvtColor(img, grayImg, cv::COLOR_RGB2GRAY);


// Assert that we work with 8 bit images
Expand Down
2 changes: 1 addition & 1 deletion lsd_slam_core/src/main_on_images.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ int main( int argc, char** argv )

for(unsigned int i=0;i<files.size();i++)
{
cv::Mat imageDist = cv::imread(files[i], CV_LOAD_IMAGE_GRAYSCALE);
cv::Mat imageDist = cv::imread(files[i], cv::IMREAD_GRAYSCALE);

if(imageDist.rows != h_inp || imageDist.cols != w_inp)
{
Expand Down
12 changes: 6 additions & 6 deletions lsd_slam_core/src/util/globalFuncs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,11 +49,11 @@ void printMessageOnCVImage(cv::Mat &image, std::string line1,std::string line2)
for(int y=image.rows-30; y<image.rows;y++)
image.at<cv::Vec3b>(y,x) *= 0.5;

cv::putText(image, line2, cvPoint(10,image.rows-5),
CV_FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(200,200,250), 1, 8);
cv::putText(image, line2, cv::Point(10,image.rows-5),
cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(200,200,250), 1, 8);

cv::putText(image, line1, cvPoint(10,image.rows-18),
CV_FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(200,200,250), 1, 8);
cv::putText(image, line1, cv::Point(10,image.rows-18),
cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(200,200,250), 1, 8);
}


Expand All @@ -71,7 +71,7 @@ cv::Mat getDepthRainbowPlot(const float* idepth, const float* idepthVar, const f
cv::Mat keyFrameImage(height, width, CV_32F, const_cast<float*>(gray));
cv::Mat keyFrameImage8u;
keyFrameImage.convertTo(keyFrameImage8u, CV_8UC1);
cv::cvtColor(keyFrameImage8u, res, CV_GRAY2RGB);
cv::cvtColor(keyFrameImage8u, res, cv::COLOR_GRAY2RGB);
}
else
fillCvMat(&res,cv::Vec3b(255,170,168));
Expand Down Expand Up @@ -136,7 +136,7 @@ cv::Mat getVarRedGreenPlot(const float* idepthVar, const float* gray, int width,
cv::Mat keyFrameImage(height, width, CV_32F, const_cast<float*>(gray));
cv::Mat keyFrameImage8u;
keyFrameImage.convertTo(keyFrameImage8u, CV_8UC1);
cv::cvtColor(keyFrameImage8u, res, CV_GRAY2RGB);
cv::cvtColor(keyFrameImage8u, res, cv::COLOR_GRAY2RGB);
}
else
fillCvMat(&res,cv::Vec3b(255,170,168));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -884,7 +884,7 @@ void drawRichKeypoints(const cv::Mat& src, std::vector<cv::KeyPoint>& kpts, cv::

cv::Mat grayFrame;
cvtColor(src, grayFrame, CV_RGB2GRAY);
cvtColor(grayFrame, dst, CV_GRAY2RGB);
cvtColor(grayFrame, dst, cv::COLOR_GRAY2RGB);

if (kpts.size() == 0) {
return;
Expand Down
Loading