From 3e684b298b284bb825b84a410c03f4b2dbbe49c6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Sch=C3=BCtte?= Date: Mon, 13 Nov 2017 18:52:10 +0100 Subject: [PATCH] Add proto3 installation to jenkins Dockerfile. (#590) [RFC=0000](https://github.com/googlecartographer/rfcs/blob/master/text/0000-proto3-transition.md) --- cartographer_ros/cartographer_ros/node_main.cc | 5 +++-- .../cartographer_ros/occupancy_grid_node_main.cc | 3 ++- cartographer_ros/cartographer_ros/time_conversion_test.cc | 2 +- jenkins/Dockerfile.kinetic | 3 +++ 4 files changed, 9 insertions(+), 4 deletions(-) diff --git a/cartographer_ros/cartographer_ros/node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc index c05f355..904d5ab 100644 --- a/cartographer_ros/cartographer_ros/node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -31,8 +31,9 @@ DEFINE_string(map_filename, "", "If non-empty, filename of a map to load."); DEFINE_bool( start_trajectory_with_default_topics, true, "Enable to immediately start the first trajectory with default topics."); -DEFINE_string(save_map_filename, "", - "If non-empty, serialize state and write it to disk before shutting down."); +DEFINE_string( + save_map_filename, "", + "If non-empty, serialize state and write it to disk before shutting down."); namespace cartographer_ros { namespace { diff --git a/cartographer_ros/cartographer_ros/occupancy_grid_node_main.cc b/cartographer_ros/cartographer_ros/occupancy_grid_node_main.cc index 0a0a4a5..66e74fd 100644 --- a/cartographer_ros/cartographer_ros/occupancy_grid_node_main.cc +++ b/cartographer_ros/cartographer_ros/occupancy_grid_node_main.cc @@ -194,7 +194,8 @@ void Node::PublishOccupancyGrid(const std::string& frame_id, occupancy_grid.info.origin.orientation.y = 0.; occupancy_grid.info.origin.orientation.z = 0.; - const uint32_t* pixel_data = reinterpret_cast(cairo_image_surface_get_data(surface)); + const uint32_t* pixel_data = + reinterpret_cast(cairo_image_surface_get_data(surface)); occupancy_grid.data.reserve(width * height); for (int y = height - 1; y >= 0; --y) { for (int x = 0; x < width; ++x) { diff --git a/cartographer_ros/cartographer_ros/time_conversion_test.cc b/cartographer_ros/cartographer_ros/time_conversion_test.cc index 5ab36c5..3b2d572 100644 --- a/cartographer_ros/cartographer_ros/time_conversion_test.cc +++ b/cartographer_ros/cartographer_ros/time_conversion_test.cc @@ -27,7 +27,7 @@ namespace { TEST(TimeConversion, testToRos) { std::vector values = {0, 1469091375, 1466481821, 1462101382, - 1468238899}; + 1468238899}; for (int64_t seconds_since_epoch : values) { ::ros::Time ros_now; ros_now.fromSec(seconds_since_epoch); diff --git a/jenkins/Dockerfile.kinetic b/jenkins/Dockerfile.kinetic index 7e374ce..b37add5 100644 --- a/jenkins/Dockerfile.kinetic +++ b/jenkins/Dockerfile.kinetic @@ -37,6 +37,9 @@ COPY cartographer_rviz/package.xml catkin_ws/src/cartographer_ros/cartographer_r COPY scripts/install_debs.sh cartographer_ros/scripts/ RUN cartographer_ros/scripts/install_debs.sh && rm -rf /var/lib/apt/lists/* +# Install proto3. +RUN /catkin_ws/src/cartographer/scripts/install_proto3.sh + # Build, install, and test all packages individually to allow caching. The # ordering of these steps must match the topological package ordering as # determined by Catkin.