Skip to content

Commit

Permalink
(Upgrade) remove <-march=native> flag because it causes crash on ROS …
Browse files Browse the repository at this point in the history
…noetic
  • Loading branch information
duyanwei committed Jan 31, 2023
1 parent efdb13d commit 6c27f21
Show file tree
Hide file tree
Showing 6 changed files with 57 additions and 12 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@ IF(${CMAKE_SYSTEM_PROCESSOR} MATCHES "arm")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wl,--no-as-needed -pthread -fopenmp -Wall -O3 -ffast-math -flto -march=armv8-a+crypto -mcpu=cortex-a57+crypto")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wl,--no-as-needed -pthread -fopenmp -Wall -O3 -ffast-math -flto -march=armv8-a+crypto -mcpu=cortex-a57+crypto")
ELSE()
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wl,--no-as-needed -pthread -fopenmp -Wall -O3 -march=native ")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wl,--no-as-needed -pthread -fopenmp -Wall -O3 -march=native")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wl,--no-as-needed -pthread -fopenmp -Wall -O3")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wl,--no-as-needed -pthread -fopenmp -Wall -O3")
ENDIF()

# Add CUDA support
Expand Down
55 changes: 50 additions & 5 deletions Examples/ROS/GF_ORB_SLAM2/src/ros_stereo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,42 @@ class ImageGrabber
#ifdef FRAME_WITH_INFO_PUBLISH
ros::Publisher mpFrameWithInfoPublisher;
#endif

// Added by yanwei, save tracking latency
std::vector<double> vTimesTrack;
std::vector<pair<double, double> > vStampedTimesTrack;

void saveStats(const std::string& path_traj)
{
// Tracking time statistics
sort(vTimesTrack.begin(),vTimesTrack.end());
float totaltime = 0;
int proccIm = vTimesTrack.size();
for(int ni=0; ni<proccIm; ni++)
{
totaltime+=vTimesTrack[ni];
}

// save to stats
{
std::ofstream myfile(path_traj + "_stats.txt");
myfile << std::setprecision(6) << -1 << " "
<< proccIm << " "
<< totaltime / proccIm << " "
<< vTimesTrack[proccIm/2] << " "
<< vTimesTrack.front() << " "
<< vTimesTrack.back() << " ";
myfile.close();

myfile.open(path_traj + "_Log_Latency.txt");
myfile << std::setprecision(20);
for (const auto& m : vStampedTimesTrack)
{
myfile << m.first << " " << m.second << "\n";
}
myfile.close();
}
}

};

Expand Down Expand Up @@ -227,6 +263,9 @@ int main(int argc, char **argv)

cout << "ros_stereo: done with spin!" << endl;

// save stats
igb.saveStats(std::string(argv[8]));

// Save camera trajectory
SLAM.SaveKeyFrameTrajectoryTUM( std::string(argv[8]) + "_KeyFrameTrajectory.txt" );
SLAM.SaveTrackingLog( std::string(argv[8]) + "_Log.txt" );
Expand Down Expand Up @@ -380,13 +419,19 @@ double latency_trans = ros::Time::now().toSec() - msgLeft->header.stamp.toSec();
pose = mpSLAM->TrackStereo(cv_ptrLeft->image,cv_ptrRight->image,cv_ptrLeft->header.stamp.toSec());
}

if (pose.empty())
return;

double latency_total = ros::Time::now().toSec() - cv_ptrLeft->header.stamp.toSec();
double latency_total = ros::Time::now().toSec() - cv_ptrLeft->header.stamp.toSec();
{
const double track_latency = latency_total - latency_trans;
vTimesTrack.emplace_back(track_latency);
vStampedTimesTrack.emplace_back(cv_ptrLeft->header.stamp.toSec(), track_latency);
}
// ROS_INFO("ORB-SLAM Tracking Latency: %.03f sec", ros::Time::now().toSec() - cv_ptrLeft->header.stamp.toSec());
// ROS_INFO("Image Transmision Latency: %.03f sec; Total Tracking Latency: %.03f sec", latency_trans, latency_total);
ROS_INFO("Pose Tracking Latency: %.03f sec", latency_total - latency_trans);
if (pose.empty())
{
return;
}
ROS_INFO("Pose Tracking Latency: %.03f sec", latency_total - latency_trans);

/*
// std::cout << "broadcast pose!" << std::endl;
Expand Down
2 changes: 1 addition & 1 deletion Examples/Stereo/stereo_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -215,7 +215,7 @@ int main(int argc, char **argv)
<< vTimesTrack.back() << " ";
myfile.close();

myfile.open(path_traj + "_timeLog.txt");
myfile.open(path_traj + "_Log_Latency.txt");
myfile << std::setprecision(20);
for (const auto& m : vStampedTimesTrack)
{
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ Now build the GF-ORB-SLAM2 package

cd ~/catkin_ws

catkin build -j8 -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-O3 -DNDEBUG -march=native" -DCMAKE_C_FLAGS_RELEASE="-O3 -DNDEBUG -march=native" -DENABLE_CUDA_IN_OPENCV=False
catkin build -j8 -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-O3 -DNDEBUG" -DCMAKE_C_FLAGS_RELEASE="-O3 -DNDEBUG" -DCMAKE_CXX_STANDARD=14 -DENABLE_CUDA_IN_OPENCV=False

Convert vocabulary file to binary for fast loading

Expand Down
4 changes: 2 additions & 2 deletions Thirdparty/g2o/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ IF(${CMAKE_SYSTEM_PROCESSOR} MATCHES "arm")
SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3 -ffast-math -flto -march=armv8-a+crypto -mcpu=cortex-a57+crypto ")
SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -O3 -ffast-math -flto -march=armv8-a+crypto -mcpu=cortex-a57+crypto")
ELSE()
SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3 -march=native ")
SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -O3 -march=native")
SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3")
SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -O3")
ENDIF()


Expand Down
2 changes: 1 addition & 1 deletion compile_flag.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,4 @@


# compile command
catkin build -j2 -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-O3 -DNDEBUG -march=native" -DCMAKE_C_FLAGS_RELEASE="-O3 -DNDEBUG -march=native" -DENABLE_CUDA_IN_OPENCV=False
catkin build -j2 -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-O3 -DNDEBUG" -DCMAKE_C_FLAGS_RELEASE="-O3 -DNDEBUG" -DCMAKE_CXX_STANDARD=14 -DENABLE_CUDA_IN_OPENCV=False

0 comments on commit 6c27f21

Please sign in to comment.