Skip to content

Commit b5e7eba

Browse files
author
Giseop Kim
authored
Merge pull request #16 from harveybia/main
Fix for #15 and OpenCV 4.0 compatibility
2 parents 7ee4ac9 + 213f3fc commit b5e7eba

9 files changed

+53
-56
lines changed

.gitignore

+5-4
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,9 @@
11
build
2-
Log/*.png
3-
Log/*.txt
4-
Log/*.csv
5-
Log/*.pdf
2+
FAST-LIO/Log/*.png
3+
FAST-LIO/Log/*.txt
4+
FAST-LIO/Log/*.csv
5+
FAST-LIO/Log/*.pdf
66
.vscode/c_cpp_properties.json
77
.vscode/settings.json
88
PCD/*.pcd
9+
*.pyc

FAST-LIO/rviz_cfg/loam_livox.rviz

+17-21
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ Panels:
1616
- /Odometry1/Odometry1/Covariance1/Orientation1
1717
- /MarkerArray1/Namespaces1
1818
Splitter Ratio: 0.6432291865348816
19-
Tree Height: 1146
19+
Tree Height: 1137
2020
- Class: rviz/Selection
2121
Name: Selection
2222
- Class: rviz/Tool Properties
@@ -61,7 +61,8 @@ Visualization Manager:
6161
Plane Cell Count: 40
6262
Reference Frame: <Fixed Frame>
6363
Value: false
64-
- Class: rviz/Axes
64+
- Alpha: 1
65+
Class: rviz/Axes
6566
Enabled: false
6667
Length: 0.699999988079071
6768
Name: Axes
@@ -85,9 +86,7 @@ Visualization Manager:
8586
Enabled: true
8687
Invert Rainbow: false
8788
Max Color: 255; 255; 255
88-
Max Intensity: 163
8989
Min Color: 0; 0; 0
90-
Min Intensity: 0
9190
Name: surround
9291
Position Transformer: XYZ
9392
Queue Size: 1
@@ -115,9 +114,7 @@ Visualization Manager:
115114
Enabled: true
116115
Invert Rainbow: true
117116
Max Color: 255; 255; 255
118-
Max Intensity: 0
119117
Min Color: 0; 0; 0
120-
Min Intensity: 0
121118
Name: currPoints
122119
Position Transformer: XYZ
123120
Queue Size: 100000
@@ -145,9 +142,7 @@ Visualization Manager:
145142
Enabled: false
146143
Invert Rainbow: false
147144
Max Color: 255; 255; 255
148-
Max Intensity: 151
149145
Min Color: 0; 0; 0
150-
Min Intensity: 0
151146
Name: PointCloud2
152147
Position Transformer: XYZ
153148
Queue Size: 10
@@ -185,6 +180,7 @@ Visualization Manager:
185180
Keep: 1
186181
Name: Odometry
187182
Position Tolerance: 0.0010000000474974513
183+
Queue Size: 10
188184
Shape:
189185
Alpha: 1
190186
Axes Length: 1
@@ -200,7 +196,8 @@ Visualization Manager:
200196
Value: true
201197
Enabled: true
202198
Name: Odometry
203-
- Class: rviz/Axes
199+
- Alpha: 1
200+
Class: rviz/Axes
204201
Enabled: true
205202
Length: 0.699999988079071
206203
Name: Axes
@@ -224,6 +221,7 @@ Visualization Manager:
224221
Z: 0
225222
Pose Color: 25; 255; 255
226223
Pose Style: None
224+
Queue Size: 10
227225
Radius: 0.029999999329447746
228226
Shaft Diameter: 0.4000000059604645
229227
Shaft Length: 0.4000000059604645
@@ -275,9 +273,7 @@ Visualization Manager:
275273
Enabled: false
276274
Invert Rainbow: false
277275
Max Color: 138; 226; 52
278-
Max Intensity: 248
279276
Min Color: 138; 226; 52
280-
Min Intensity: 0
281277
Name: PointCloud2
282278
Position Transformer: XYZ
283279
Queue Size: 10
@@ -326,33 +322,33 @@ Visualization Manager:
326322
Views:
327323
Current:
328324
Class: rviz/ThirdPersonFollower
329-
Distance: 247.9972686767578
325+
Distance: 76.899658203125
330326
Enable Stereo Rendering:
331327
Stereo Eye Separation: 0.05999999865889549
332328
Stereo Focal Distance: 1
333329
Swap Stereo Eyes: false
334330
Value: false
331+
Field of View: 0.7853981852531433
335332
Focal Point:
336-
X: 165.75035095214844
337-
Y: -44.61741256713867
338-
Z: 1.1274762073298916e-5
333+
X: 0
334+
Y: 0
335+
Z: 0
339336
Focal Shape Fixed Size: false
340337
Focal Shape Size: 0.05000000074505806
341338
Invert Z Axis: false
342339
Name: Current View
343340
Near Clip Distance: 0.009999999776482582
344341
Pitch: 1.5697963237762451
345342
Target Frame: global
346-
Value: ThirdPersonFollower (rviz)
347-
Yaw: 4.727225303649902
343+
Yaw: 2.980398416519165
348344
Saved: ~
349345
Window Geometry:
350346
Displays:
351347
collapsed: false
352-
Height: 1385
348+
Height: 1376
353349
Hide Left Dock: false
354350
Hide Right Dock: false
355-
QMainWindow State: 000000ff00000000fd0000000400000000000001c8000004b7fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000004b7000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009bd00000052fc0100000002fb0000000800540069006d00650100000000000009bd000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000697000004b700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
351+
QMainWindow State: 000000ff00000000fd0000000400000000000001c8000004aefc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000004ae000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004aefc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000004ae000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009b800000052fc0100000002fb0000000800540069006d00650100000000000009b8000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000692000004ae00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
356352
Selection:
357353
collapsed: false
358354
Time:
@@ -361,6 +357,6 @@ Window Geometry:
361357
collapsed: false
362358
Views:
363359
collapsed: false
364-
Width: 2493
365-
X: 67
360+
Width: 2488
361+
X: 72
366362
Y: 27

SC-PGO/launch/aloam_mulran.launch

+1-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
<remap from="/velodyne_points" to="/os1_points"/>
2525

2626
<!-- utils -->
27-
<param name="save_directory" type="string" value="/home/user/Documents/catkin2021/catkin_scaloam_util/data/"/> <!-- CHANGE THIS and end with / -->
27+
<param name="save_directory" type="string" value="$(env HOME)/Documents/catkin2021/catkin_scaloam_util/data/"/> <!-- CHANGE THIS and end with / -->
2828

2929
<!-- nodes -->
3030
<node pkg="aloam_velodyne" type="ascanRegistration" name="ascanRegistration" output="screen" /> <!-- A-LOAM -->

SC-PGO/launch/fastlio_ouster64.launch

+1-1
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
<remap from="/cloud_for_scancontext" to="/cloud_registered_lidar"/> <!-- because ScanContext requires lidar-ego-centric coordinate for the better performance -->
3131

3232
<!-- utils -->
33-
<param name="save_directory" type="string" value="/home/user/Desktop/catkin_fastlio_slam/data/"/> <!-- CHANGE THIS and end with / -->
33+
<param name="save_directory" type="string" value="$(env HOME)/Desktop/catkin_fastlio_slam/data/"/> <!-- CHANGE THIS and end with / -->
3434

3535
<!-- nodes -->
3636
<node pkg="aloam_velodyne" type="alaserPGO" name="alaserPGO" output="screen" /> <!-- Scan Context-based PGO -->

SC-PGO/src/kittiHelper.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -58,12 +58,12 @@ int main(int argc, char** argv)
5858

5959
ros::Publisher pubOdomGT = n.advertise<nav_msgs::Odometry> ("/odometry_gt", 5);
6060
nav_msgs::Odometry odomGT;
61-
odomGT.header.frame_id = "/camera_init";
61+
odomGT.header.frame_id = "camera_init";
6262
odomGT.child_frame_id = "/ground_truth";
6363

6464
ros::Publisher pubPathGT = n.advertise<nav_msgs::Path> ("/path_gt", 5);
6565
nav_msgs::Path pathGT;
66-
pathGT.header.frame_id = "/camera_init";
66+
pathGT.header.frame_id = "camera_init";
6767

6868
std::string timestamp_path = "sequences/" + sequence_number + "/times.txt";
6969
std::ifstream timestamp_file(dataset_folder + timestamp_path, std::ifstream::in);
@@ -88,9 +88,9 @@ int main(int argc, char** argv)
8888
float timestamp = stof(line);
8989
std::stringstream left_image_path, right_image_path;
9090
left_image_path << dataset_folder << "sequences/" + sequence_number + "/image_0/" << std::setfill('0') << std::setw(6) << line_num << ".png";
91-
cv::Mat left_image = cv::imread(left_image_path.str(), CV_LOAD_IMAGE_GRAYSCALE);
91+
cv::Mat left_image = cv::imread(left_image_path.str(), cv::IMREAD_GRAYSCALE);
9292
right_image_path << dataset_folder << "sequences/" + sequence_number + "/image_1/" << std::setfill('0') << std::setw(6) << line_num << ".png";
93-
cv::Mat right_image = cv::imread(left_image_path.str(), CV_LOAD_IMAGE_GRAYSCALE);
93+
cv::Mat right_image = cv::imread(left_image_path.str(), cv::IMREAD_GRAYSCALE);
9494

9595
std::getline(ground_truth_file, line);
9696
std::stringstream pose_stream(line);
@@ -153,7 +153,7 @@ int main(int argc, char** argv)
153153
sensor_msgs::PointCloud2 laser_cloud_msg;
154154
pcl::toROSMsg(laser_cloud, laser_cloud_msg);
155155
laser_cloud_msg.header.stamp = ros::Time().fromSec(timestamp);
156-
laser_cloud_msg.header.frame_id = "/camera_init";
156+
laser_cloud_msg.header.frame_id = "camera_init";
157157
pub_laser_cloud.publish(laser_cloud_msg);
158158

159159
sensor_msgs::ImagePtr image_left_msg = cv_bridge::CvImage(laser_cloud_msg.header, "mono8", left_image).toImageMsg();

SC-PGO/src/laserMapping.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -216,7 +216,7 @@ void laserOdometryHandler(const nav_msgs::Odometry::ConstPtr &laserOdometry)
216216
Eigen::Vector3d t_w_curr = q_wmap_wodom * t_wodom_curr + t_wmap_wodom;
217217

218218
nav_msgs::Odometry odomAftMapped;
219-
odomAftMapped.header.frame_id = "/camera_init";
219+
odomAftMapped.header.frame_id = "camera_init";
220220
odomAftMapped.child_frame_id = "/aft_mapped";
221221
odomAftMapped.header.stamp = laserOdometry->header.stamp;
222222
odomAftMapped.pose.pose.orientation.x = q_w_curr.x();
@@ -817,7 +817,7 @@ void process()
817817
sensor_msgs::PointCloud2 laserCloudSurround3;
818818
pcl::toROSMsg(*laserCloudSurround, laserCloudSurround3);
819819
laserCloudSurround3.header.stamp = ros::Time().fromSec(timeLaserOdometry);
820-
laserCloudSurround3.header.frame_id = "/camera_init";
820+
laserCloudSurround3.header.frame_id = "camera_init";
821821
pubLaserCloudSurround.publish(laserCloudSurround3);
822822
}
823823

@@ -832,14 +832,14 @@ void process()
832832
sensor_msgs::PointCloud2 laserCloudMsg;
833833
pcl::toROSMsg(laserCloudMap, laserCloudMsg);
834834
laserCloudMsg.header.stamp = ros::Time().fromSec(timeLaserOdometry);
835-
laserCloudMsg.header.frame_id = "/camera_init";
835+
laserCloudMsg.header.frame_id = "camera_init";
836836
pubLaserCloudMap.publish(laserCloudMsg);
837837
}
838838

839839
sensor_msgs::PointCloud2 laserCloudFullRes3Local;
840840
pcl::toROSMsg(*laserCloudFullRes, laserCloudFullRes3Local);
841841
laserCloudFullRes3Local.header.stamp = ros::Time().fromSec(timeLaserOdometry);
842-
laserCloudFullRes3Local.header.frame_id = "/camera_init";
842+
laserCloudFullRes3Local.header.frame_id = "camera_init";
843843
pubLaserCloudFullResLocal.publish(laserCloudFullRes3Local);
844844

845845
int laserCloudFullResNum = laserCloudFullRes->points.size();
@@ -851,15 +851,15 @@ void process()
851851
sensor_msgs::PointCloud2 laserCloudFullRes3;
852852
pcl::toROSMsg(*laserCloudFullRes, laserCloudFullRes3);
853853
laserCloudFullRes3.header.stamp = ros::Time().fromSec(timeLaserOdometry);
854-
laserCloudFullRes3.header.frame_id = "/camera_init";
854+
laserCloudFullRes3.header.frame_id = "camera_init";
855855
pubLaserCloudFullRes.publish(laserCloudFullRes3);
856856

857857
//printf("mapping pub time %f ms \n", t_pub.toc());
858858

859859
//printf("whole mapping time %f ms ++++++++++\n", t_whole.toc());
860860

861861
nav_msgs::Odometry odomAftMapped;
862-
odomAftMapped.header.frame_id = "/camera_init";
862+
odomAftMapped.header.frame_id = "camera_init";
863863
odomAftMapped.child_frame_id = "/aft_mapped";
864864
odomAftMapped.header.stamp = ros::Time().fromSec(timeLaserOdometry);
865865
odomAftMapped.pose.pose.orientation.x = q_w_curr.x();
@@ -881,7 +881,7 @@ void process()
881881
laserAfterMappedPose.pose = odomAftMapped.pose.pose;
882882

883883
laserAfterMappedPath.header.stamp = odomAftMapped.header.stamp;
884-
laserAfterMappedPath.header.frame_id = "/camera_init";
884+
laserAfterMappedPath.header.frame_id = "camera_init";
885885
laserAfterMappedPath.poses.push_back(laserAfterMappedPose);
886886
pubLaserAfterMappedPath.publish(laserAfterMappedPath);
887887

@@ -896,7 +896,7 @@ void process()
896896
q.setY(q_w_curr.y());
897897
q.setZ(q_w_curr.z());
898898
transform.setRotation(q);
899-
br.sendTransform(tf::StampedTransform(transform, odomAftMapped.header.stamp, "/camera_init", "/aft_mapped"));
899+
br.sendTransform(tf::StampedTransform(transform, odomAftMapped.header.stamp, "camera_init", "/aft_mapped"));
900900

901901
frameCount++;
902902
}

SC-PGO/src/laserOdometry.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -509,7 +509,7 @@ int main(int argc, char **argv)
509509

510510
// publish odometry
511511
nav_msgs::Odometry laserOdometry;
512-
laserOdometry.header.frame_id = "/camera_init";
512+
laserOdometry.header.frame_id = "camera_init";
513513
laserOdometry.child_frame_id = "/laser_odom";
514514
laserOdometry.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);
515515
laserOdometry.pose.pose.orientation.x = q_w_curr.x();
@@ -526,7 +526,7 @@ int main(int argc, char **argv)
526526
laserPose.pose = laserOdometry.pose.pose;
527527
laserPath.header.stamp = laserOdometry.header.stamp;
528528
laserPath.poses.push_back(laserPose);
529-
laserPath.header.frame_id = "/camera_init";
529+
laserPath.header.frame_id = "camera_init";
530530
pubLaserPath.publish(laserPath);
531531

532532
// transform corner features and plane features to the scan end point

SC-PGO/src/laserPosegraphOptimization.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -293,7 +293,7 @@ void pubPath( void )
293293
// pub odom and path
294294
nav_msgs::Odometry odomAftPGO;
295295
nav_msgs::Path pathAftPGO;
296-
pathAftPGO.header.frame_id = "/camera_init";
296+
pathAftPGO.header.frame_id = "camera_init";
297297
mKF.lock();
298298
// for (int node_idx=0; node_idx < int(keyframePosesUpdated.size()) - 1; node_idx++) // -1 is just delayed visualization (because sometimes mutexed while adding(push_back) a new one)
299299
for (int node_idx=0; node_idx < recentIdxUpdated; node_idx++) // -1 is just delayed visualization (because sometimes mutexed while adding(push_back) a new one)
@@ -302,7 +302,7 @@ void pubPath( void )
302302
// const gtsam::Pose3& pose_est = isamCurrentEstimate.at<gtsam::Pose3>(node_idx);
303303

304304
nav_msgs::Odometry odomAftPGOthis;
305-
odomAftPGOthis.header.frame_id = "/camera_init";
305+
odomAftPGOthis.header.frame_id = "camera_init";
306306
odomAftPGOthis.child_frame_id = "/aft_pgo";
307307
odomAftPGOthis.header.stamp = ros::Time().fromSec(keyframeTimes.at(node_idx));
308308
odomAftPGOthis.pose.pose.position.x = pose_est.x;
@@ -316,7 +316,7 @@ void pubPath( void )
316316
poseStampAftPGO.pose = odomAftPGOthis.pose.pose;
317317

318318
pathAftPGO.header.stamp = odomAftPGOthis.header.stamp;
319-
pathAftPGO.header.frame_id = "/camera_init";
319+
pathAftPGO.header.frame_id = "camera_init";
320320
pathAftPGO.poses.push_back(poseStampAftPGO);
321321
}
322322
mKF.unlock();
@@ -332,7 +332,7 @@ void pubPath( void )
332332
q.setY(odomAftPGO.pose.pose.orientation.y);
333333
q.setZ(odomAftPGO.pose.pose.orientation.z);
334334
transform.setRotation(q);
335-
br.sendTransform(tf::StampedTransform(transform, odomAftPGO.header.stamp, "/camera_init", "/aft_pgo"));
335+
br.sendTransform(tf::StampedTransform(transform, odomAftPGO.header.stamp, "camera_init", "/aft_pgo"));
336336
} // pubPath
337337

338338
void updatePoses(void)
@@ -436,12 +436,12 @@ std::optional<gtsam::Pose3> doICPVirtualRelative( int _loop_kf_idx, int _curr_kf
436436
// loop verification
437437
sensor_msgs::PointCloud2 cureKeyframeCloudMsg;
438438
pcl::toROSMsg(*cureKeyframeCloud, cureKeyframeCloudMsg);
439-
cureKeyframeCloudMsg.header.frame_id = "/camera_init";
439+
cureKeyframeCloudMsg.header.frame_id = "camera_init";
440440
pubLoopScanLocal.publish(cureKeyframeCloudMsg);
441441

442442
sensor_msgs::PointCloud2 targetKeyframeCloudMsg;
443443
pcl::toROSMsg(*targetKeyframeCloud, targetKeyframeCloudMsg);
444-
targetKeyframeCloudMsg.header.frame_id = "/camera_init";
444+
targetKeyframeCloudMsg.header.frame_id = "camera_init";
445445
pubLoopSubmapLocal.publish(targetKeyframeCloudMsg);
446446

447447
// ICP Settings
@@ -750,7 +750,7 @@ void pubMap(void)
750750

751751
sensor_msgs::PointCloud2 laserCloudMapPGOMsg;
752752
pcl::toROSMsg(*laserCloudMapPGO, laserCloudMapPGOMsg);
753-
laserCloudMapPGOMsg.header.frame_id = "/camera_init";
753+
laserCloudMapPGOMsg.header.frame_id = "camera_init";
754754
pubMapAftPGO.publish(laserCloudMapPGOMsg);
755755
}
756756

0 commit comments

Comments
 (0)