Skip to content

Commit f4a47e9

Browse files
authored
Feature/refactoring (#80)
* Refactor for parameter support and better logging. * Add initializeMap function * Fix log output in graph slam and add develop branch CI * Use ros official docker in CI * Install git in CI * Fix CI
1 parent f75a186 commit f4a47e9

File tree

5 files changed

+135
-132
lines changed

5 files changed

+135
-132
lines changed

.github/workflows/main.yml

Lines changed: 36 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -4,49 +4,44 @@ on:
44
push:
55
branches:
66
- humble
7+
- develop
78
pull_request:
89
branches:
910
- humble
11+
- develop
1012

1113
jobs:
12-
job1:
13-
name: Build
14-
runs-on: ubuntu-22.04
15-
# container:
16-
# image: ubuntu:jammy
17-
steps:
18-
- name: ROS2 Install
19-
run: |
20-
sudo apt update && sudo apt install locales
21-
sudo locale-gen en_US en_US.UTF-8
22-
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
23-
export LANG=en_US.UTF-8
24-
sudo apt update && sudo apt install curl gnupg2 lsb-release
25-
curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
26-
sudo sh -c 'echo "deb [arch=amd64,arm64] http://packages.ros.org/ros2/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/ros2-latest.list'
27-
sudo apt update
28-
sudo apt install ros-humble-desktop
29-
source /opt/ros/humble/setup.bash
30-
- uses: actions/checkout@v1
31-
with:
32-
submodules: true
33-
- name: Copy repository
34-
run: |
35-
mkdir -p ~/ros2_ws/src/lidarslam_ros2
36-
cp -rf . ~/ros2_ws/src/lidarslam_ros2
37-
- name: Install dependencies
38-
run: |
39-
source /opt/ros/humble/setup.bash
40-
sudo apt install -y python3-rosdep2
41-
rosdep update
42-
cd ~/ros2_ws/src
43-
rosdep install -r -y --from-paths . --ignore-src
44-
- name: Build packages
45-
run: |
46-
source /opt/ros/humble/setup.bash
47-
# Install colcon
48-
# Ref: https://index.ros.org/doc/ros2/Tutorials/Colcon-Tutorial/
49-
sudo apt install python3-colcon-common-extensions
50-
cd ~/ros2_ws
51-
colcon build
52-
source ~/ros2_ws/install/setup.bash
14+
job1:
15+
name: Build
16+
runs-on: ubuntu-22.04
17+
container: ros:humble-ros-core
18+
steps:
19+
- name: Install Git
20+
run: |
21+
apt-get update
22+
apt-get install -y git
23+
shell: bash
24+
- uses: actions/checkout@v2
25+
with:
26+
submodules: true
27+
- name: Copy repository
28+
run: |
29+
mkdir -p ~/ros2_ws/src/lidarslam_ros2
30+
cp -rf . ~/ros2_ws/src/lidarslam_ros2
31+
shell: bash
32+
- name: Install dependencies
33+
run: |
34+
apt-get install -y python3-rosdep
35+
rosdep init
36+
rosdep update
37+
cd ~/ros2_ws/src
38+
rosdep install -r -y --from-paths . --ignore-src
39+
shell: bash
40+
- name: Build packages
41+
run: |
42+
source /opt/ros/humble/setup.bash
43+
apt-get install -y python3-colcon-common-extensions
44+
cd ~/ros2_ws
45+
colcon build
46+
source ~/ros2_ws/install/setup.bash
47+
shell: bash

graph_based_slam/src/graph_based_slam_component.cpp

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ GraphBasedSlamComponent::GraphBasedSlamComponent(const rclcpp::NodeOptions & opt
7070
ndt->setNeighborhoodSearchMethod(pclomp::DIRECT7);
7171
if (ndt_num_threads > 0) {ndt->setNumThreads(ndt_num_threads);}
7272
registration_ = ndt;
73-
} else {
73+
} else if (registration_method == "GICP") {
7474
boost::shared_ptr<pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>>
7575
gicp(new pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>());
7676
gicp->setMaxCorrespondenceDistance(30);
@@ -80,6 +80,9 @@ GraphBasedSlamComponent::GraphBasedSlamComponent(const rclcpp::NodeOptions & opt
8080
gicp->setEuclideanFitnessEpsilon(1e-6);
8181
gicp->setRANSACIterations(0);
8282
registration_ = gicp;
83+
} else {
84+
RCLCPP_ERROR(get_logger(), "invalid registration_method");
85+
exit(1);
8386
}
8487

8588
initializePubSub();
@@ -155,7 +158,7 @@ void GraphBasedSlamComponent::searchLoop()
155158

156159
if(debug_flag_)
157160
{
158-
std::cout << "searching Loop, num_submaps:" << num_submaps << std::endl;
161+
RCLCPP_INFO(get_logger(), "searching Loop, num_submaps:%d", num_submaps);
159162
}
160163

161164
double min_fitness_score = std::numeric_limits<double>::max();
@@ -244,20 +247,15 @@ void GraphBasedSlamComponent::searchLoop()
244247
loop_edges_.push_back(loop_edge);
245248

246249
std::cout << "---" << std::endl;
247-
std::cout << "PoseAdjustment" << std::endl;
248-
std::cout << "distance:" << min_submap.distance << ", score:" << fitness_score << std::endl;
249-
std::cout << "id_loop_point 1:" << id_min << std::endl;
250-
std::cout << "id_loop_point 2:" << num_submaps - 1 << std::endl;
250+
std::cout << "PoseAdjustment distance:" << min_submap.distance << ", score:" << fitness_score << std::endl;
251+
std::cout << "id_loop_point 1:" << id_min << " id_loop_point 2:" << num_submaps - 1 << std::endl;
251252
std::cout << "final transformation:" << std::endl;
252253
std::cout << registration_->getFinalTransformation() << std::endl;
253254
doPoseAdjustment(map_array_msg, use_save_map_in_loop_);
254255

255256
return;
256257
}
257-
258-
std::cout << "-" << std::endl;
259-
std::cout << "min_submap_distance:" << min_submap.distance << std::endl;
260-
std::cout << "min_fitness_score:" << fitness_score << std::endl;
258+
std::cout << "min_submap_distance:" << min_submap.distance << " min_fitness_score:" << fitness_score << std::endl;
261259
}
262260
}
263261

lidarslam/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ install(
9292
DESTINATION share/${PROJECT_NAME}
9393
)
9494

95-
install(TARGETS
95+
install(TARGETS
9696
lidarslam
9797
DESTINATION lib/${PROJECT_NAME}
9898
)

scanmatcher/include/scanmatcher/scanmatcher_component.h

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -114,8 +114,9 @@ namespace graphslam
114114
rclcpp::Publisher < nav_msgs::msg::Path > ::SharedPtr path_pub_;
115115

116116
void initializePubSub();
117+
void initializeMap(const pcl::PointCloud <pcl::PointXYZI>::Ptr & cloud_ptr, const std_msgs::msg::Header & header);
117118
void receiveCloud(
118-
const pcl::PointCloud < pcl::PointXYZI > ::ConstPtr & input_cloud_ptr,
119+
const pcl::PointCloud < pcl::PointXYZI> ::ConstPtr & input_cloud_ptr,
119120
const rclcpp::Time stamp);
120121
void receiveImu(const sensor_msgs::msg::Imu imu_msg);
121122
void publishMapAndPose(
@@ -124,7 +125,7 @@ namespace graphslam
124125
const rclcpp::Time stamp
125126
);
126127
Eigen::Matrix4f getTransformation(const geometry_msgs::msg::Pose pose);
127-
void publishMap();
128+
void publishMap(const lidarslam_msgs::msg::MapArray & map_array_msg, const std::string & map_frame_id);
128129
void updateMap(
129130
const pcl::PointCloud < pcl::PointXYZI > ::ConstPtr cloud_ptr,
130131
const Eigen::Matrix4f final_transformation,
@@ -173,6 +174,6 @@ namespace graphslam
173174
LidarUndistortion lidar_undistortion_;
174175

175176
};
176-
}
177+
} // namespace graphslam
177178

178179
#endif //GS_SM_COMPONENT_H_INCLUDED

0 commit comments

Comments
 (0)