diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..63b4b68 --- /dev/null +++ b/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) [year] [fullname] + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. \ No newline at end of file diff --git a/README.md b/README.md index 095279b..b300108 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,17 @@ This repo contains a ROS2 metapackage that estimates the camera pose with respect to the world frame exploiting Aruco Markers. This package implements a [ROS2 Service](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Services/Understanding-ROS2-Services.html) that collects a set of $N$ measurements of the aruco position and orientation and computes the average. Then the resulting camera position and orientation is sent as the service response to the calling node. Each required parameter is loaded from a `.yaml` file. # Installation +Install dependecies: +- [ROS2](https://docs.ros.org/en/humble/Installation.html) +- OpenCV + ``` + sudo apt install libopencv-dev -y + ``` +- ROS CVBridge + ``` + sudo apt-get install ros-$ROS_DISTRO-cv-bridge + ``` + The following code will build the `calibration_srv` interface and the c++ package of the program: ``` cd /src @@ -16,7 +27,7 @@ Then print your aruco using the 4x4 dictionary. You can use this [website](https # Run the service server In a sourced terminal run ``` -ros2 launch aruco_camera_pose_estimator aruco_camera_pose_estimator.launch.py +ros2 launch aruco_camera_pose_estimator_cpp aruco_camera_pose_estimator.launch.py ``` In another sourced terminal call the service ``` diff --git a/aruco_camera_pose_estimator_cpp/CMakeLists.txt b/aruco_camera_pose_estimator_cpp/CMakeLists.txt index 61197b5..65f71be 100755 --- a/aruco_camera_pose_estimator_cpp/CMakeLists.txt +++ b/aruco_camera_pose_estimator_cpp/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(aruco_camera_pose_estimator) +project(aruco_camera_pose_estimator_cpp) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -20,11 +20,11 @@ find_package(cv_bridge REQUIRED) find_package(OpenCV REQUIRED) find_package(calibration_srv REQUIRED) -add_executable(aruco_camera_pose_estimator +add_executable(aruco_camera_pose_estimator_cpp src/pose_service.cpp src/image_processor.cpp ) -ament_target_dependencies(aruco_camera_pose_estimator +ament_target_dependencies(aruco_camera_pose_estimator_cpp rclcpp sensor_msgs geometry_msgs @@ -35,12 +35,12 @@ include_directories( ${OpenCV_INCLUDE_DIRS} include ) -target_link_libraries(aruco_camera_pose_estimator +target_link_libraries(aruco_camera_pose_estimator_cpp Eigen3::Eigen ${OpenCV_LIBS} ) install(TARGETS - aruco_camera_pose_estimator + aruco_camera_pose_estimator_cpp DESTINATION lib/${PROJECT_NAME} ) install( diff --git a/aruco_camera_pose_estimator_cpp/launch/aruco_camera_pose_estimator.launch.py b/aruco_camera_pose_estimator_cpp/launch/aruco_camera_pose_estimator.launch.py index f50c3c0..f868c5c 100644 --- a/aruco_camera_pose_estimator_cpp/launch/aruco_camera_pose_estimator.launch.py +++ b/aruco_camera_pose_estimator_cpp/launch/aruco_camera_pose_estimator.launch.py @@ -16,8 +16,8 @@ def generate_launch_description(): ld = LaunchDescription() aruco_calibration_node = Node( - package="aruco_camera_pose_estimator", - executable="aruco_camera_pose_estimator", + package="aruco_camera_pose_estimator_cpp", + executable="aruco_camera_pose_estimator_cpp", # get parameters from yaml file parameters=[ParameterFile(get_package_share_directory('aruco_camera_pose_estimator') + "/config/config.yaml"), ParameterFile(get_package_share_directory('aruco_camera_pose_estimator') + "/config/calibration_params.yaml") diff --git a/aruco_camera_pose_estimator_cpp/package.xml b/aruco_camera_pose_estimator_cpp/package.xml index d9a178d..0c2f01c 100755 --- a/aruco_camera_pose_estimator_cpp/package.xml +++ b/aruco_camera_pose_estimator_cpp/package.xml @@ -1,15 +1,15 @@ - aruco_camera_pose_estimator - 0.0.0 - TODO: Package description + aruco_camera_pose_estimator_cpp + 0.0.1 + ROS2 package for estimating the position and orientation of the camera using Aruco + markers hydran00 - TODO: License declaration + MIT ament_cmake - ament_cmake_python - calibration_srv - tf2_ros + cv_bridge + calibration_srv rclcpp ament_cmake