Skip to content

Commit

Permalink
Merge branch 'hybridpath_to_CMakeLists'
Browse files Browse the repository at this point in the history
  • Loading branch information
Mokaz committed Mar 28, 2024
1 parent 5f81a88 commit b69f5ce
Show file tree
Hide file tree
Showing 14 changed files with 83 additions and 82 deletions.
35 changes: 35 additions & 0 deletions guidance/hybridpath_guidance/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
cmake_minimum_required(VERSION 3.8)
project(hybridpath_guidance)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake_python REQUIRED)
find_package(rclpy REQUIRED)
find_package(vortex_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)

ament_python_install_package(${PROJECT_NAME})

install(DIRECTORY
launch
config
DESTINATION share/${PROJECT_NAME}
)

install(PROGRAMS
hybridpath_guidance/hybridpath_guidance_node.py
DESTINATION lib/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_pytest REQUIRED)
ament_add_pytest_test(python_tests tests)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
endif()

ament_package()
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
import numpy as np
import rclpy
from rclpy.node import Node
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
def generate_launch_description():
hybridpath_guidance_node = Node(
package='hybridpath_guidance',
executable='hybridpath_guidance_node',
executable='hybridpath_guidance_node.py',
name='hybridpath_guidance_node',
parameters=[os.path.join(get_package_share_directory('hybridpath_guidance'),'config','hybridpath_guidance_config.yaml')],
output='screen',
Expand Down
9 changes: 3 additions & 6 deletions guidance/hybridpath_guidance/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
<package format="3">
<name>hybridpath_guidance</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">vortex</maintainer>
<description>This package provides the implementation of hybrid path guidance for the Vortex ASV.</description>
<maintainer email="[email protected]">vortex</maintainer>
<license>MIT</license>

<depend>rclpy</depend>
Expand All @@ -13,12 +13,9 @@
<depend>geometry_msgs</depend>
<depend>vortex_msgs</depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
<build_type>ament_cmake</build_type>
</export>
</package>
Empty file.
4 changes: 0 additions & 4 deletions guidance/hybridpath_guidance/setup.cfg

This file was deleted.

30 changes: 0 additions & 30 deletions guidance/hybridpath_guidance/setup.py

This file was deleted.

35 changes: 35 additions & 0 deletions motion/hybridpath_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
cmake_minimum_required(VERSION 3.8)
project(hybridpath_controller)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake_python REQUIRED)
find_package(rclpy REQUIRED)
find_package(vortex_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)

ament_python_install_package(${PROJECT_NAME})

install(DIRECTORY
launch
config
DESTINATION share/${PROJECT_NAME}
)

install(PROGRAMS
hybridpath_controller/hybridpath_controller_node.py
DESTINATION lib/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_pytest REQUIRED)
ament_add_pytest_test(python_tests tests)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
endif()

ament_package()
2 changes: 2 additions & 0 deletions motion/hybridpath_controller/hybridpath_controller/hybridpath_controller_node.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import rclpy
import numpy as np
from rclpy.node import Node
Expand Down
2 changes: 1 addition & 1 deletion motion/hybridpath_controller/launch/hybridpath_controller.launch.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
def generate_launch_description():
hybridpath_controller_node = Node(
package='hybridpath_controller',
executable='hybridpath_controller_node',
executable='hybridpath_controller_node.py',
name='hybridpath_controller_node',
parameters=[os.path.join(get_package_share_directory('hybridpath_controller'),'config','hybridpath_controller_config.yaml')],
output='screen',
Expand Down
11 changes: 5 additions & 6 deletions motion/hybridpath_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,22 +3,21 @@
<package format="3">
<name>hybridpath_controller</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">vortex</maintainer>
<description>This package provides the implementation of hybrid path controller for the Vortex ASV.</description>
<maintainer email="[email protected]">vortex</maintainer>
<license>MIT</license>

<buildtool_depend>ament_cmake_python</buildtool_depend>

<depend>rclpy</depend>
<depend>python-transforms3d-pip</depend>
<depend>geometry_msgs</depend>
<depend>vortex_msgs</depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>


<export>
<build_type>ament_python</build_type>
<build_type>ament_cmake</build_type>
</export>
</package>
Empty file.
4 changes: 0 additions & 4 deletions motion/hybridpath_controller/setup.cfg

This file was deleted.

30 changes: 0 additions & 30 deletions motion/hybridpath_controller/setup.py

This file was deleted.

0 comments on commit b69f5ce

Please sign in to comment.