Skip to content

Commit

Permalink
Merge pull request #34 from seanyen/seanyen/windows
Browse files Browse the repository at this point in the history
[melodic-devel] Windows bringup
  • Loading branch information
k-okada authored Sep 30, 2021
2 parents ee1e33b + 25e662f commit 5e9a6f7
Show file tree
Hide file tree
Showing 38 changed files with 173 additions and 101 deletions.
40 changes: 37 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,19 @@ project(openslam_gmapping)
## Find catkin macros and libraries
find_package(catkin REQUIRED)

include(GenerateExportHeader)
set(EXPORT_HEADER_DIR "${CATKIN_DEVEL_PREFIX}/include")
file(MAKE_DIRECTORY "${EXPORT_HEADER_DIR}")

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
catkin_package(
INCLUDE_DIRS include
INCLUDE_DIRS
include
${EXPORT_HEADER_DIR}
LIBRARIES utils sensor_base sensor_odometry sensor_range log configfile scanmatcher gridfastslam
)

Expand All @@ -20,7 +26,10 @@ catkin_package(

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(include)
include_directories(
include
${EXPORT_HEADER_DIR}
)

#SUBDIRS=utils sensor log configfile scanmatcher gridfastslam gui

Expand Down Expand Up @@ -152,9 +161,13 @@ target_link_libraries(gridfastslam
# )

## Mark executables and/or libraries for installation
install(TARGETS utils autoptr_test sensor_base sensor_odometry sensor_range sensor_range log log_test log_plot scanstudio2carmen rdk2carmen configfile configfile_test scanmatcher scanmatch_test icptest gridfastslam gfs2log gfs2rec gfs2neff
install(TARGETS utils sensor_base sensor_odometry sensor_range log configfile scanmatcher gridfastslam
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
)

install(TARGETS autoptr_test log_test log_plot scanstudio2carmen rdk2carmen configfile_test scanmatch_test icptest gfs2log gfs2rec gfs2neff
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Expand All @@ -165,6 +178,27 @@ install(DIRECTORY include/gmapping
PATTERN ".svn" EXCLUDE
)

generate_export_header(utils
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/utils/utils_export.h)
generate_export_header(sensor_base
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/sensor/sensor_base/sensor_base_export.h)
generate_export_header(sensor_odometry
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/sensor/sensor_odometry/sensor_odometry_export.h)
generate_export_header(sensor_range
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/sensor/sensor_range/sensor_range_export.h)
generate_export_header(log
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/log/log_export.h)
generate_export_header(configfile
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/configfile/configfile_export.h)
generate_export_header(scanmatcher
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/scanmatcher/scanmatcher_export.h)
generate_export_header(gridfastslam
EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/gmapping/gridfastslam/gridfastslam_export.h)

install(DIRECTORY
${EXPORT_HEADER_DIR}/
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})

#############
## Testing ##
#############
Expand Down
10 changes: 5 additions & 5 deletions carmenwrapper/carmenwrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ bool CarmenWrapper::getReading(RangeReading& reading){
sem_wait(&m_dequeSem);
pthread_mutex_lock(&m_mutex);
if (!m_rangeDeque.empty()){
// cerr << __PRETTY_FUNCTION__ << ": queue size=" <<m_rangeDeque.size() << endl;
// cerr << __func__ << ": queue size=" <<m_rangeDeque.size() << endl;
reading=m_rangeDeque.front();
m_rangeDeque.pop_front();
present=true;
Expand Down Expand Up @@ -213,7 +213,7 @@ void CarmenWrapper::robot_frontlaser_handler(carmen_robot_laser_message* frontla
m_rangeSensor=new RangeSensor("FLASER",frontlaser->num_readings, res, OrientedPoint(0,0,0), 0, 89.9);
m_sensorMap.insert(make_pair(string("FLASER"), m_rangeSensor));
cout << __PRETTY_FUNCTION__
cout << __func__
<< ": FrontLaser configured."
<< " Readings " << m_rangeSensor->beams().size()
<< " Resolution " << res << endl;
Expand Down Expand Up @@ -241,7 +241,7 @@ void CarmenWrapper::robot_rearlaser_handler(carmen_robot_laser_message* rearlase
m_rangeSensor=new RangeSensor("FLASER",frontlaser->num_readings, res, OrientedPoint(0,0,0), 0, 89.9);
m_sensorMap.insert(make_pair(string("FLASER"), m_rangeSensor));
cout << __PRETTY_FUNCTION__
cout << __func__
<< ": FrontLaser configured."
<< " Readings " << m_rangeSensor->beams().size()
<< " Resolution " << res << endl;
Expand Down Expand Up @@ -324,7 +324,7 @@ RangeReading CarmenWrapper::carmen2reading(const carmen_robot_laser_message& msg
m_frontLaser->updateBeamsLookup();
m_sensorMap.insert(make_pair(sensorName, m_frontLaser));

cout << __PRETTY_FUNCTION__
cout << __func__
<< ": " << sensorName <<" configured."
<< " Readings " << m_frontLaser->beams().size()
<< " Resolution " << res << endl;
Expand All @@ -346,7 +346,7 @@ RangeReading CarmenWrapper::carmen2reading(const carmen_robot_laser_message& msg
m_rearLaser->updateBeamsLookup();
m_sensorMap.insert(make_pair(sensorName, m_rearLaser));

cout << __PRETTY_FUNCTION__
cout << __func__
<< ": " << sensorName <<" configured."
<< " Readings " << m_rearLaser->beams().size()
<< " Resolution " << res << endl;
Expand Down
6 changes: 3 additions & 3 deletions gfs-carmen/gfs-carmen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <gmapping/utils/orientedboundingbox.h>
#include <gmapping/configfile/configfile.h>

#define DEBUG cout << __PRETTY_FUNCTION__
#define DEBUG cout << __func__

/*
Example file for interfacing carmen, and gfs.
Expand Down Expand Up @@ -227,10 +227,10 @@ int main(int argc, const char * const * argv){
cerr << "Best Particle is " << best_idx << " with weight " << best_weight << endl;
*/
cerr << __PRETTY_FUNCTION__ << "CLONING... " << endl;
cerr << __func__ << "CLONING... " << endl;
GridSlamProcessor* newProcessor=processor->clone();
cerr << "DONE" << endl;
cerr << __PRETTY_FUNCTION__ << "DELETING... " << endl;
cerr << __func__ << "DELETING... " << endl;
delete processor;
cerr << "DONE" << endl;
processor=newProcessor;
Expand Down
24 changes: 12 additions & 12 deletions gridfastslam/gridslamprocessor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ using namespace std;
m_obsSigmaGain=gsp.m_obsSigmaGain;

#ifdef MAP_CONSISTENCY_CHECK
cerr << __PRETTY_FUNCTION__ << ": trajectories copy.... ";
cerr << __func__ << ": trajectories copy.... ";
#endif
TNodeVector v=gsp.getTrajectories();
for (unsigned int i=0; i<v.size(); i++){
Expand All @@ -97,7 +97,7 @@ using namespace std;

GridSlamProcessor* GridSlamProcessor::clone() const {
# ifdef MAP_CONSISTENCY_CHECK
cerr << __PRETTY_FUNCTION__ << ": performing preclone_fit_test" << endl;
cerr << __func__ << ": performing preclone_fit_test" << endl;
typedef std::map<autoptr< Array2D<PointAccumulator> >::reference* const, int> PointerMap;
PointerMap pmap;
for (ParticleVector::const_iterator it=m_particles.begin(); it!=m_particles.end(); it++){
Expand All @@ -116,17 +116,17 @@ using namespace std;
}
}
}
cerr << __PRETTY_FUNCTION__ << ": Number of allocated chunks" << pmap.size() << endl;
cerr << __func__ << ": Number of allocated chunks" << pmap.size() << endl;
for(PointerMap::const_iterator it=pmap.begin(); it!=pmap.end(); it++)
assert(it->first->shares==(unsigned int)it->second);

cerr << __PRETTY_FUNCTION__ << ": SUCCESS, the error is somewhere else" << endl;
cerr << __func__ << ": SUCCESS, the error is somewhere else" << endl;
# endif
GridSlamProcessor* cloned=new GridSlamProcessor(*this);

# ifdef MAP_CONSISTENCY_CHECK
cerr << __PRETTY_FUNCTION__ << ": trajectories end" << endl;
cerr << __PRETTY_FUNCTION__ << ": performing afterclone_fit_test" << endl;
cerr << __func__ << ": trajectories end" << endl;
cerr << __func__ << ": performing afterclone_fit_test" << endl;
ParticleVector::const_iterator jt=cloned->m_particles.begin();
for (ParticleVector::const_iterator it=m_particles.begin(); it!=m_particles.end(); it++){
const ScanMatcherMap& m1(it->map);
Expand All @@ -143,14 +143,14 @@ using namespace std;
}
}
}
cerr << __PRETTY_FUNCTION__ << ": SUCCESS, the error is somewhere else" << endl;
cerr << __func__ << ": SUCCESS, the error is somewhere else" << endl;
# endif
return cloned;
}

GridSlamProcessor::~GridSlamProcessor(){
cerr << __PRETTY_FUNCTION__ << ": Start" << endl;
cerr << __PRETTY_FUNCTION__ << ": Deleting tree" << endl;
cerr << __func__ << ": Start" << endl;
cerr << __func__ << ": Deleting tree" << endl;
for (std::vector<Particle>::iterator it=m_particles.begin(); it!=m_particles.end(); it++){
#ifdef TREE_CONSISTENCY_CHECK
TNode* node=it->node;
Expand All @@ -164,7 +164,7 @@ using namespace std;
}

# ifdef MAP_CONSISTENCY_CHECK
cerr << __PRETTY_FUNCTION__ << ": performing predestruction_fit_test" << endl;
cerr << __func__ << ": performing predestruction_fit_test" << endl;
typedef std::map<autoptr< Array2D<PointAccumulator> >::reference* const, int> PointerMap;
PointerMap pmap;
for (ParticleVector::const_iterator it=m_particles.begin(); it!=m_particles.end(); it++){
Expand All @@ -183,10 +183,10 @@ using namespace std;
}
}
}
cerr << __PRETTY_FUNCTION__ << ": Number of allocated chunks" << pmap.size() << endl;
cerr << __func__ << ": Number of allocated chunks" << pmap.size() << endl;
for(PointerMap::const_iterator it=pmap.begin(); it!=pmap.end(); it++)
assert(it->first->shares>=(unsigned int)it->second);
cerr << __PRETTY_FUNCTION__ << ": SUCCESS, the error is somewhere else" << endl;
cerr << __func__ << ": SUCCESS, the error is somewhere else" << endl;
# endif
}

Expand Down
18 changes: 9 additions & 9 deletions gridfastslam/gridslamprocessor_tree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,22 +57,22 @@ GridSlamProcessor::TNodeVector GridSlamProcessor::getTrajectories() const{
assert(newnode->childs==0);
if (newnode->parent){
parentCache.insert(make_pair(newnode->parent, newnode));
//cerr << __PRETTY_FUNCTION__ << ": node " << newnode->parent << " flag=" << newnode->parent->flag<< endl;
//cerr << __func__ << ": node " << newnode->parent << " flag=" << newnode->parent->flag<< endl;
if (! newnode->parent->flag){
//cerr << __PRETTY_FUNCTION__ << ": node " << newnode->parent << " flag=" << newnode->parent->flag<< endl;
//cerr << __func__ << ": node " << newnode->parent << " flag=" << newnode->parent->flag<< endl;
newnode->parent->flag=true;
border.push_back(newnode->parent);
}
}
}

//cerr << __PRETTY_FUNCTION__ << ": border.size(INITIAL)=" << border.size() << endl;
//cerr << __PRETTY_FUNCTION__ << ": parentCache.size()=" << parentCache.size() << endl;
//cerr << __func__ << ": border.size(INITIAL)=" << border.size() << endl;
//cerr << __func__ << ": parentCache.size()=" << parentCache.size() << endl;
while (! border.empty()){
//cerr << __PRETTY_FUNCTION__ << ": border.size(PREPROCESS)=" << border.size() << endl;
//cerr << __PRETTY_FUNCTION__ << ": parentCache.size(PREPROCESS)=" << parentCache.size() << endl;
//cerr << __func__ << ": border.size(PREPROCESS)=" << border.size() << endl;
//cerr << __func__ << ": parentCache.size(PREPROCESS)=" << parentCache.size() << endl;
const TNode* node=border.front();
//cerr << __PRETTY_FUNCTION__ << ": node " << node << endl;
//cerr << __func__ << ": node " << node << endl;
border.pop_front();
if (! node)
continue;
Expand All @@ -91,7 +91,7 @@ GridSlamProcessor::TNodeVector GridSlamProcessor::getTrajectories() const{
}
////cerr << endl;
parentCache.erase(p.first, p.second);
//cerr << __PRETTY_FUNCTION__ << ": parentCache.size(POSTERASE)=" << parentCache.size() << endl;
//cerr << __func__ << ": parentCache.size(POSTERASE)=" << parentCache.size() << endl;
assert(childs==newnode->childs);

//unmark the node
Expand All @@ -104,7 +104,7 @@ GridSlamProcessor::TNodeVector GridSlamProcessor::getTrajectories() const{
}
//insert the parent in the cache
}
//cerr << __PRETTY_FUNCTION__ << " : checking cloned trajectories" << endl;
//cerr << __func__ << " : checking cloned trajectories" << endl;
for (unsigned int i=0; i<v.size(); i++){
TNode* node= v[i];
while (node){
Expand Down
4 changes: 3 additions & 1 deletion gui/gfs_nogui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,9 @@
*****************************************************************/


#include <unistd.h>
#ifndef _WIN32
#include <unistd.h>
#endif
#include "gmapping/gui/gsp_thread.h"

using namespace GMapping;
Expand Down
2 changes: 1 addition & 1 deletion gui/gsp_thread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <gmapping/carmenwrapper/carmenwrapper.h>
#endif

#define DEBUG cout << __PRETTY_FUNCTION__
#define DEBUG cout << __func__

using namespace std;

Expand Down
2 changes: 1 addition & 1 deletion gui/qparticleviewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ void QParticleViewer::drawMap(const ScanMatcherMap& map){
Point wmax=Point(pic2map(IntPoint(m_pixmap->width()/2,-m_pixmap->height()/2)));
IntPoint imin=map.world2map(wmin);
IntPoint imax=map.world2map(wmax);
/* cout << __PRETTY_FUNCTION__ << endl;
/* cout << __func__ << endl;
cout << " viewCenter=" << viewCenter.x << "," << viewCenter.y << endl;
cout << " wmin=" << wmin.x << "," << wmin.y << " wmax=" << wmax.x << "," << wmax.y << endl;
cout << " imin=" << imin.x << "," << imin.y << " imax=" << imax.x << "," << imax.y << endl;
Expand Down
5 changes: 3 additions & 2 deletions include/gmapping/configfile/configfile.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,11 @@
#include <iostream>
#include <string>
#include <map>
#include <gmapping/configfile/configfile_export.h>

namespace GMapping{

class AutoVal {
class CONFIGFILE_EXPORT AutoVal {
public:
AutoVal() {};
explicit AutoVal(const std::string&);
Expand Down Expand Up @@ -62,7 +63,7 @@ class AutoVal {
std::string m_value;
};

class ConfigFile {
class CONFIGFILE_EXPORT ConfigFile {
std::map<std::string,AutoVal> m_content;

public:
Expand Down
10 changes: 5 additions & 5 deletions include/gmapping/grid/array2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ Array2D<Cell,debug>::Array2D(int xsize, int ysize){
m_cells=0;
}
if (debug){
std::cerr << __PRETTY_FUNCTION__ << std::endl;
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
}
Expand All @@ -79,7 +79,7 @@ Array2D<Cell,debug> & Array2D<Cell,debug>::operator=(const Array2D<Cell,debug> &
m_cells[x][y]=g.m_cells[x][y];

if (debug){
std::cerr << __PRETTY_FUNCTION__ << std::endl;
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
}
Expand All @@ -97,7 +97,7 @@ Array2D<Cell,debug>::Array2D(const Array2D<Cell,debug> & g){
m_cells[x][y]=g.m_cells[x][y];
}
if (debug){
std::cerr << __PRETTY_FUNCTION__ << std::endl;
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
}
Expand All @@ -106,7 +106,7 @@ Array2D<Cell,debug>::Array2D(const Array2D<Cell,debug> & g){
template <class Cell, const bool debug>
Array2D<Cell,debug>::~Array2D(){
if (debug){
std::cerr << __PRETTY_FUNCTION__ << std::endl;
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
}
Expand All @@ -121,7 +121,7 @@ Array2D<Cell,debug>::~Array2D(){
template <class Cell, const bool debug>
void Array2D<Cell,debug>::clear(){
if (debug){
std::cerr << __PRETTY_FUNCTION__ << std::endl;
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
}
Expand Down
Loading

0 comments on commit 5e9a6f7

Please sign in to comment.