Skip to content

Commit

Permalink
Installed scripts, some minor fixes and warnings (#6)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Sep 11, 2023
1 parent 85d28ba commit e88295b
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 2 deletions.
6 changes: 6 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion scripts/publisher.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
Empty file modified scripts/subscriber_old_school.py
100644 → 100755
Empty file.
2 changes: 1 addition & 1 deletion src/my_encoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <point_cloud_transport/point_cloud_codec.hpp>

int main(int argc, char ** argv)
int main(int /*argc*/, char ** /*argv*/)
{
auto logger_ = rclcpp::get_logger("my_encoder");

Expand Down

0 comments on commit e88295b

Please sign in to comment.