diff --git a/CMakeLists.txt b/CMakeLists.txt index e0007ec..6f8ca76 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -52,6 +52,12 @@ install( DESTINATION share/${PROJECT_NAME} ) +install(PROGRAMS + scripts/publisher.py + scripts/subscriber_old_school.py + DESTINATION lib/${PROJECT_NAME} +) + # linting tests if(BUILD_TESTING) find_package(ament_cmake_copyright REQUIRED) diff --git a/scripts/publisher.py b/scripts/publisher.py old mode 100644 new mode 100755 index 143cdfc..4d59484 --- a/scripts/publisher.py +++ b/scripts/publisher.py @@ -52,7 +52,7 @@ def pointCloud2ToString(msg: PointCloud2): rclpy.init(args=sys.argv) - bag_path = argv[1] + bag_path = sys.argv[1] serialization_format='cdr' storage_options = rosbag2_py.StorageOptions( diff --git a/scripts/subscriber_old_school.py b/scripts/subscriber_old_school.py old mode 100644 new mode 100755 diff --git a/src/my_encoder.cpp b/src/my_encoder.cpp index 7dab6bc..4de177c 100644 --- a/src/my_encoder.cpp +++ b/src/my_encoder.cpp @@ -16,7 +16,7 @@ #include -int main(int argc, char ** argv) +int main(int /*argc*/, char ** /*argv*/) { auto logger_ = rclcpp::get_logger("my_encoder");