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

Refactoring and CI update #80

Merged
merged 6 commits into from
Nov 26, 2023
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
77 changes: 36 additions & 41 deletions .github/workflows/main.yml
Original file line number Diff line number Diff line change
Expand Up @@ -4,49 +4,44 @@ on:
push:
branches:
- humble
- develop
pull_request:
branches:
- humble
- develop

jobs:
job1:
name: Build
runs-on: ubuntu-22.04
# container:
# image: ubuntu:jammy
steps:
- name: ROS2 Install
run: |
sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
sudo apt update && sudo apt install curl gnupg2 lsb-release
curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
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'
sudo apt update
sudo apt install ros-humble-desktop
source /opt/ros/humble/setup.bash
- uses: actions/checkout@v1
with:
submodules: true
- name: Copy repository
run: |
mkdir -p ~/ros2_ws/src/lidarslam_ros2
cp -rf . ~/ros2_ws/src/lidarslam_ros2
- name: Install dependencies
run: |
source /opt/ros/humble/setup.bash
sudo apt install -y python3-rosdep2
rosdep update
cd ~/ros2_ws/src
rosdep install -r -y --from-paths . --ignore-src
- name: Build packages
run: |
source /opt/ros/humble/setup.bash
# Install colcon
# Ref: https://index.ros.org/doc/ros2/Tutorials/Colcon-Tutorial/
sudo apt install python3-colcon-common-extensions
cd ~/ros2_ws
colcon build
source ~/ros2_ws/install/setup.bash
job1:
name: Build
runs-on: ubuntu-22.04
container: ros:humble-ros-core
steps:
- name: Install Git
run: |
apt-get update
apt-get install -y git
shell: bash
- uses: actions/checkout@v2
with:
submodules: true
- name: Copy repository
run: |
mkdir -p ~/ros2_ws/src/lidarslam_ros2
cp -rf . ~/ros2_ws/src/lidarslam_ros2
shell: bash
- name: Install dependencies
run: |
apt-get install -y python3-rosdep
rosdep init
rosdep update
cd ~/ros2_ws/src
rosdep install -r -y --from-paths . --ignore-src
shell: bash
- name: Build packages
run: |
source /opt/ros/humble/setup.bash
apt-get install -y python3-colcon-common-extensions
cd ~/ros2_ws
colcon build
source ~/ros2_ws/install/setup.bash
shell: bash
18 changes: 8 additions & 10 deletions graph_based_slam/src/graph_based_slam_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ GraphBasedSlamComponent::GraphBasedSlamComponent(const rclcpp::NodeOptions & opt
ndt->setNeighborhoodSearchMethod(pclomp::DIRECT7);
if (ndt_num_threads > 0) {ndt->setNumThreads(ndt_num_threads);}
registration_ = ndt;
} else {
} else if (registration_method == "GICP") {
boost::shared_ptr<pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>>
gicp(new pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>());
gicp->setMaxCorrespondenceDistance(30);
Expand All @@ -80,6 +80,9 @@ GraphBasedSlamComponent::GraphBasedSlamComponent(const rclcpp::NodeOptions & opt
gicp->setEuclideanFitnessEpsilon(1e-6);
gicp->setRANSACIterations(0);
registration_ = gicp;
} else {
RCLCPP_ERROR(get_logger(), "invalid registration_method");
exit(1);
}

initializePubSub();
Expand Down Expand Up @@ -155,7 +158,7 @@ void GraphBasedSlamComponent::searchLoop()

if(debug_flag_)
{
std::cout << "searching Loop, num_submaps:" << num_submaps << std::endl;
RCLCPP_INFO(get_logger(), "searching Loop, num_submaps:%d", num_submaps);
}

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

std::cout << "---" << std::endl;
std::cout << "PoseAdjustment" << std::endl;
std::cout << "distance:" << min_submap.distance << ", score:" << fitness_score << std::endl;
std::cout << "id_loop_point 1:" << id_min << std::endl;
std::cout << "id_loop_point 2:" << num_submaps - 1 << std::endl;
std::cout << "PoseAdjustment distance:" << min_submap.distance << ", score:" << fitness_score << std::endl;
std::cout << "id_loop_point 1:" << id_min << " id_loop_point 2:" << num_submaps - 1 << std::endl;
std::cout << "final transformation:" << std::endl;
std::cout << registration_->getFinalTransformation() << std::endl;
doPoseAdjustment(map_array_msg, use_save_map_in_loop_);

return;
}

std::cout << "-" << std::endl;
std::cout << "min_submap_distance:" << min_submap.distance << std::endl;
std::cout << "min_fitness_score:" << fitness_score << std::endl;
std::cout << "min_submap_distance:" << min_submap.distance << " min_fitness_score:" << fitness_score << std::endl;
}
}

Expand Down
2 changes: 1 addition & 1 deletion lidarslam/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ install(
DESTINATION share/${PROJECT_NAME}
)

install(TARGETS
install(TARGETS
lidarslam
DESTINATION lib/${PROJECT_NAME}
)
Expand Down
7 changes: 4 additions & 3 deletions scanmatcher/include/scanmatcher/scanmatcher_component.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,8 +114,9 @@ namespace graphslam
rclcpp::Publisher < nav_msgs::msg::Path > ::SharedPtr path_pub_;

void initializePubSub();
void initializeMap(const pcl::PointCloud <pcl::PointXYZI>::Ptr & cloud_ptr, const std_msgs::msg::Header & header);
void receiveCloud(
const pcl::PointCloud < pcl::PointXYZI > ::ConstPtr & input_cloud_ptr,
const pcl::PointCloud < pcl::PointXYZI> ::ConstPtr & input_cloud_ptr,
const rclcpp::Time stamp);
void receiveImu(const sensor_msgs::msg::Imu imu_msg);
void publishMapAndPose(
Expand All @@ -124,7 +125,7 @@ namespace graphslam
const rclcpp::Time stamp
);
Eigen::Matrix4f getTransformation(const geometry_msgs::msg::Pose pose);
void publishMap();
void publishMap(const lidarslam_msgs::msg::MapArray & map_array_msg, const std::string & map_frame_id);
void updateMap(
const pcl::PointCloud < pcl::PointXYZI > ::ConstPtr cloud_ptr,
const Eigen::Matrix4f final_transformation,
Expand Down Expand Up @@ -173,6 +174,6 @@ namespace graphslam
LidarUndistortion lidar_undistortion_;

};
}
} // namespace graphslam

#endif //GS_SM_COMPONENT_H_INCLUDED
Loading
Loading