Skip to content

Commit

Permalink
Update CI to run on noble and address uncrustify issues (#73)
Browse files Browse the repository at this point in the history
* Update to noble and lint some

Signed-off-by: Yadunund <yadunund@intrinsic.ai>

* Manually lint more

Signed-off-by: Yadunund <yadunund@intrinsic.ai>

* Fix copyright test

Signed-off-by: Yadunund <yadunund@intrinsic.ai>

---------

Signed-off-by: Yadunund <yadunund@intrinsic.ai>
  • Loading branch information
Yadunund committed Jun 2, 2024
1 parent 79d15ab commit f6ed4d7
Show file tree
Hide file tree
Showing 6 changed files with 30 additions and 12 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/build.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,5 +20,5 @@ jobs:
rmf_visualization_obstacles
rmf_visualization_rviz2_plugins
rmf_visualization_schedule
dist-matrix: '[{"ros_distribution": "rolling", "ubuntu_distribution": "jammy"}]'
dist-matrix: '[{"ros_distribution": "rolling", "ubuntu_distribution": "noble"}]'

Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
# Copyright 2024 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import rclpy
from rclpy.node import Node

Expand Down
2 changes: 1 addition & 1 deletion rmf_visualization_navgraphs/src/NavGraphVisualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ auto NavGraphVisualizer::FleetNavGraph::update_lane_states(

auto update_marker =
[&](const std::size_t id,
std::function<void(Marker::SharedPtr& marker)> updater)
std::function<void(Marker::SharedPtr& marker)> updater)
{
auto it = all_lane_markers.find(id);
if (it == all_lane_markers.end())
Expand Down
4 changes: 2 additions & 2 deletions rmf_visualization_rviz2_plugins/src/SchedulePanel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,8 @@ SchedulePanel::SchedulePanel(QWidget* parent)
});

_conclusion_sub = _node->create_subscription<NegotiationConclusion>(
"/rmf_traffic/negotiation_conclusion", rclcpp::SystemDefaultsQoS().keep_last(
10),
"/rmf_traffic/negotiation_conclusion",
rclcpp::SystemDefaultsQoS().keep_last(10),
[&](const NegotiationConclusion::UniquePtr msg)
{
this->recieved_conclusion(*msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -217,9 +217,10 @@ auto ScheduleDataNode::get_negotiation_trajectories(
}

rmf_traffic::RouteId route_id = 0;
const auto add_route = [&route_id, &table_view, &trajectory_elements]
(const rmf_traffic::Route& route,
rmf_traffic::schedule::ParticipantId id)
const auto add_route =
[&route_id, &table_view, &trajectory_elements]
(const rmf_traffic::Route& route,
rmf_traffic::schedule::ParticipantId id)
{
Element e {
id,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -309,9 +309,10 @@ const std::string TrajectoryServer::Implementation::parse_trajectories(
j_traj["dimensions"] = element.description.profile().footprint()
->get_characteristic_length();

auto add_segment = [&](rmf_traffic::Time finish_time,
Eigen::Vector3d finish_position,
Eigen::Vector3d finish_velocity)
auto add_segment =
[&](rmf_traffic::Time finish_time,
Eigen::Vector3d finish_position,
Eigen::Vector3d finish_velocity)
{
auto j_seg = _j_seg;
j_seg["x"] =
Expand Down Expand Up @@ -441,7 +442,8 @@ std::shared_ptr<TrajectoryServer> TrajectoryServer::make(
}

// Set up callbacks for negotiations
auto status_update_cb = [server_ptr](
auto status_update_cb =
[server_ptr](
uint64_t conflict_version,
rmf_traffic::schedule::Negotiation::Table::ViewerPtr table_view)
{
Expand Down Expand Up @@ -473,7 +475,8 @@ std::shared_ptr<TrajectoryServer> TrajectoryServer::make(
server_ptr->_pimpl->schedule_data_node->get_negotiation()->on_status_update(
std::move(status_update_cb));

auto conclusion_cb = [server_ptr](
auto conclusion_cb =
[server_ptr](
uint64_t conflict_version, bool resolved)
{
RCLCPP_DEBUG(
Expand Down

0 comments on commit f6ed4d7

Please sign in to comment.