Skip to content

Commit 86e9aeb

Browse files
itskalvikbeniaminopozzan
authored andcommitted
Update to build offboard_control.py
1 parent 2d56cb6 commit 86e9aeb

File tree

4 files changed

+16
-0
lines changed

4 files changed

+16
-0
lines changed

CMakeLists.txt

+14
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ find_package(geometry_msgs REQUIRED)
2424
find_package(px4_msgs REQUIRED)
2525
find_package(rclcpp REQUIRED)
2626
find_package(sensor_msgs REQUIRED)
27+
find_package(rclpy REQUIRED)
2728

2829
#################
2930
# Setup targets #
@@ -111,4 +112,17 @@ if(BUILD_TESTING)
111112
ament_lint_auto_find_test_dependencies()
112113
endif()
113114

115+
###########
116+
# Python ##
117+
###########
118+
119+
# Install Python modules
120+
ament_python_install_package(${PROJECT_NAME})
121+
122+
# Install Python executables
123+
install(PROGRAMS
124+
src/examples/offboard_py/offboard_control.py
125+
DESTINATION lib/${PROJECT_NAME}
126+
)
127+
114128
ament_package()

px4_ros_com/__init__.py

Whitespace-only changes.

px4_ros_com/module_to_import.py

Whitespace-only changes.

src/examples/offboard_py/offboard_control.py

100644100755
+2
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,5 @@
1+
#!/usr/bin/env python3
2+
13
import rclpy
24
from rclpy.node import Node
35
from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy, DurabilityPolicy

0 commit comments

Comments
 (0)