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

Fix: combine map problem #9

Merged
merged 1 commit into from
Aug 26, 2024
Merged
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
2 changes: 1 addition & 1 deletion src/map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1516,7 +1516,7 @@ void Map::merge(std::shared_ptr<Map> mapB){
kfIter->ids[i] = pointIdB2A[kfIter->ids[i]];
}
}
mapManager->addKeyFrame(&(*kfIter));
mapManager->addKeyFrame(&(*kfIter), true);
}
}

Expand Down
16 changes: 10 additions & 6 deletions src/tslam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ authors and should not be interpreted as representing official policies, either
or implied Andrea Settimi and Hong-Bin Yang.
*/
#include <regex>
#include <filesystem>

#include "tslam.h"
#include "utils/system.h"
Expand Down Expand Up @@ -183,15 +184,18 @@ namespace tslam{
*estimatedImageParam = TheMapA->keyframes.begin()->imageParams;
}

string basePath = outputPath;
if(std::regex_match(basePath, std::regex("\\.map$"))){
basePath.substr(0, basePath.length() - 4);
}
std::filesystem::path basePath = outputPath;

if(exportYml){
TheMapA->saveToMarkerMap(basePath + ".yml");
TheMapA->saveToMarkerMap(basePath.replace_extension("yml"));
}
if(exportPly){
TheMapA->exportToFile(basePath + ".ply",cv::Scalar(125,125,125),cv::Scalar(255,0,0),cv::Scalar(0,0,255),{1111,1195,1129,1196,1141},cv::Scalar(0,255,0));
TheMapA->exportToFile(basePath.replace_extension("ply"),
cv::Scalar(125,125,125),
cv::Scalar(255,0,0),
cv::Scalar(0,0,255),
{},
cv::Scalar(0,255,0));
}

TheMapA->saveToFile(std::move(outputPath));
Expand Down
6 changes: 3 additions & 3 deletions src/utils/mapmanager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ void MapManager::reset(){



Frame& MapManager::addKeyFrame(Frame *newPtrFrame){
Frame& MapManager::addKeyFrame(Frame *newPtrFrame, bool forceAddNewMarker){
auto getNOFValidMarkers=[this](){
int nValidMarkers=0;
for(auto &m:TheMap->map_markers)
Expand All @@ -247,9 +247,9 @@ Frame& MapManager::addKeyFrame(Frame *newPtrFrame){
};

// in localizeOnly mode, filter out the marker that is not in the map
if(System::getParams().localizeOnly){
if(!forceAddNewMarker && System::getParams().localizeOnly){
std::vector<tslam::MarkerObservation> filteredMarkers;
for(auto m : newPtrFrame->markers) {
for(const auto &m : newPtrFrame->markers) {
if (TheMap->map_markers.count(m.id)!=0){
filteredMarkers.push_back(m);
}
Expand Down
2 changes: 1 addition & 1 deletion src/utils/mapmanager.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ struct NewPointInfo{
//call whenever a new frame is avaiable.
//return 0 if nothing is done
int newFrame(Frame &kf, int32_t curkeyFrame);
Frame &addKeyFrame(Frame *f);
Frame &addKeyFrame(Frame *f, bool forceAddNewMarker = false);

//applies the changes to map require tracking to be stoped, such as removing frames or points
bool mapUpdate(void);
Expand Down
Loading