Skip to content

Commit

Permalink
Reformat with uncrustify available in noble
Browse files Browse the repository at this point in the history
Signed-off-by: Yadunund <yadunund@intrinsic.ai>
  • Loading branch information
Yadunund committed May 31, 2024
1 parent 7cceafd commit fedd853
Show file tree
Hide file tree
Showing 13 changed files with 80 additions and 74 deletions.
4 changes: 3 additions & 1 deletion rmf_task/include/rmf_task/CompositeData.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,9 @@ class CompositeData
/// instance. The defined class will contain only one field whose type is
/// specified by Type. The name of the class will be Name.
#define RMF_TASK_DEFINE_COMPONENT(Type, Name) \
struct Name { Type value; Name(Type input) : value(input) {} }
struct Name { Type value; Name(Type input)\
: value(input) {}\
}

#include <rmf_task/detail/impl_CompositeData.hpp>

Expand Down
3 changes: 2 additions & 1 deletion rmf_task/src/rmf_task/BackupFileManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,8 @@ std::optional<std::string> BackupFileManager::Robot::read() const
if (filename.compare(_pimpl->backup_file_name) != 0 &&
filename.compare(_pimpl->pre_backup_file_name) != 0)
{
throw std::runtime_error("[BackupFileManager::Robot::read] Foreign file " +
throw std::runtime_error(
"[BackupFileManager::Robot::read] Foreign file " +
filename + " found. This should be removed.");
}
}
Expand Down
10 changes: 5 additions & 5 deletions rmf_task/src/rmf_task/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,11 @@ class Log::Implementation
if (!clock)
{
clock = []()
{
return rmf_traffic::Time(
rmf_traffic::Duration(
std::chrono::system_clock::now().time_since_epoch()));
};
{
return rmf_traffic::Time(
rmf_traffic::Duration(
std::chrono::system_clock::now().time_since_epoch()));
};
}
}

Expand Down
16 changes: 8 additions & 8 deletions rmf_task/src/rmf_task/TaskPlanner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -662,16 +662,16 @@ class TaskPlanner::Implementation
initial_node->sort_invariants();

initial_node->latest_time = [&]() -> rmf_traffic::Time
{
rmf_traffic::Time latest = rmf_traffic::Time::min();
for (const auto& s : initial_states)
{
rmf_traffic::Time latest = rmf_traffic::Time::min();
for (const auto& s : initial_states)
{
if (latest < s.time().value())
latest = s.time().value();
}
if (latest < s.time().value())
latest = s.time().value();
}

return latest;
} ();
return latest;
} ();

rmf_traffic::Time wait_until = rmf_traffic::Time::max();

Expand Down
3 changes: 2 additions & 1 deletion rmf_task/src/rmf_task/internal_task_planning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,8 @@ void Candidates::update_candidate(
_candidate_map[candidate] = _value_map.insert(
{
state.time().value(),
Entry{candidate, state, wait_until, previous_state, require_charge_battery}
Entry{candidate, state, wait_until, previous_state,
require_charge_battery}
});
}

Expand Down
3 changes: 2 additions & 1 deletion rmf_task/test/integration/test_backups.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@
const std::filesystem::path backup_root_dir = "/tmp/rmf_task/test_backups";
void cleanup()
{
std::filesystem::remove_all(std::filesystem::weakly_canonical(backup_root_dir));
std::filesystem::remove_all(std::filesystem::weakly_canonical(
backup_root_dir));
}

SCENARIO("Backup file creation and clearing tests")
Expand Down
3 changes: 2 additions & 1 deletion rmf_task/test/mock/MockDelivery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,8 @@ class MockDelivery : public rmf_task::Task
const uint64_t max_phase_id = pending_phases().size();
if (phase_id < min_phase_id && phase_id > max_phase_id)
{
throw std::runtime_error("[MockDelivery::Active] phase_id given was " + std::to_string(
throw std::runtime_error(
"[MockDelivery::Active] phase_id given was " + std::to_string(
phase_id) + " not in range of " + std::to_string(
min_phase_id) + "," + std::to_string(max_phase_id) + ".");
}
Expand Down
8 changes: 4 additions & 4 deletions rmf_task/test/unit/agv/test_TaskPlanner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,10 +149,10 @@ SCENARIO("Grid World")

rmf_traffic::agv::Graph graph;
auto add_bidir_lane = [&](const std::size_t w0, const std::size_t w1)
{
graph.add_lane(w0, w1);
graph.add_lane(w1, w0);
};
{
graph.add_lane(w0, w1);
graph.add_lane(w1, w0);
};

const std::string map_name = "test_map";

Expand Down
20 changes: 10 additions & 10 deletions rmf_task_sequence/src/rmf_task_sequence/Task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -659,16 +659,16 @@ void Task::Active::_load_backup(std::string backup_state_str)
const auto start_time = _clock();

const auto failed_to_restore = [&]() -> void
{
_pending_stages.clear();
_phase_finished(
std::make_shared<rmf_task::Phase::Completed>(
rmf_task::Phase::Snapshot::make(*restore_phase),
start_time,
_clock()));

_finish_task();
};
{
_pending_stages.clear();
_phase_finished(
std::make_shared<rmf_task::Phase::Completed>(
rmf_task::Phase::Snapshot::make(*restore_phase),
start_time,
_clock()));

_finish_task();
};

const auto backup_state = nlohmann::json::parse(backup_state_str);
if (const auto result =
Expand Down
12 changes: 6 additions & 6 deletions rmf_task_sequence/src/rmf_task_sequence/events/Bundle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -310,9 +310,9 @@ void Bundle::add(const Event::InitializerPtr& initializer)
if (!initialize_from)
{
throw std::runtime_error(
"[rmf_task_sequence::Bundle::add] Use-after-free error: Event "
"initializer has already destructed, but is still being used to "
"initialize an event.");
"[rmf_task_sequence::Bundle::add] Use-after-free error: Event "
"initializer has already destructed, but is still being used to "
"initialize an event.");
}

return initiate(
Expand All @@ -337,9 +337,9 @@ void Bundle::add(const Event::InitializerPtr& initializer)
if (!initialize_from)
{
throw std::runtime_error(
"[rmf_task_sequence::Bundle::add] Use-after-free error: Event "
"initializer has already destructed, but is still being used to "
"initialize an event.");
"[rmf_task_sequence::Bundle::add] Use-after-free error: Event "
"initializer has already destructed, but is still being used to "
"initialize an event.");
}

return restore(
Expand Down
20 changes: 10 additions & 10 deletions rmf_task_sequence/src/rmf_task_sequence/events/GoToPlace.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -328,11 +328,11 @@ Header GoToPlace::Description::generate_header(
}

auto goal_name = [&](const rmf_traffic::agv::Plan::Goal& goal)
{
return rmf_task::standard_waypoint_name(
parameters.planner()->get_configuration().graph(),
goal.waypoint());
};
{
return rmf_task::standard_waypoint_name(
parameters.planner()->get_configuration().graph(),
goal.waypoint());
};

const auto goal_name_ = goal_name(_pimpl->one_of[selected_index]);

Expand Down Expand Up @@ -370,11 +370,11 @@ std::string GoToPlace::Description::destination_name(
return "<none>";

auto goal_name = [&](const rmf_traffic::agv::Plan::Goal& goal)
{
return rmf_task::standard_waypoint_name(
parameters.planner()->get_configuration().graph(),
goal.waypoint());
};
{
return rmf_task::standard_waypoint_name(
parameters.planner()->get_configuration().graph(),
goal.waypoint());
};

return std::accumulate(
std::next(_pimpl->one_of.begin()),
Expand Down
44 changes: 22 additions & 22 deletions rmf_task_sequence/src/rmf_task_sequence/events/Sequence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@ Event::StandbyPtr Sequence::Standby::initiate(
{
auto state = make_state(id, description);
const auto update = [parent_update, state]()
{
update_status(*state);
parent_update();
};
{
update_status(*state);
parent_update();
};

std::vector<Event::StandbyPtr> dependencies;
dependencies.reserve(description.dependencies().size());
Expand All @@ -62,10 +62,10 @@ Event::StandbyPtr Sequence::Standby::initiate(
std::function<void()> parent_update)
{
const auto update = [parent_update, state]()
{
update_status(*state);
parent_update();
};
{
update_status(*state);
parent_update();
};

std::vector<Event::StandbyPtr> dependencies;
dependencies.reserve(dependencies_fn.size());
Expand Down Expand Up @@ -173,10 +173,10 @@ Event::ActivePtr Sequence::Active::restore(
{
auto state = Sequence::Standby::make_state(id, description);
const auto update = [parent_update = std::move(parent_update), state]()
{
Sequence::Standby::update_status(*state);
parent_update();
};
{
Sequence::Standby::update_status(*state);
parent_update();
};

std::vector<Event::StandbyPtr> dependencies;

Expand Down Expand Up @@ -217,10 +217,10 @@ Event::ActivePtr Sequence::Active::restore(
std::move(finished));

const auto event_finished = [me = active->weak_from_this()]()
{
if (const auto self = me.lock())
self->next();
};
{
if (const auto self = me.lock())
self->next();
};

const auto& current_event_state = current_event_json["state"];
active->_current = initializer.restore(
Expand Down Expand Up @@ -383,13 +383,13 @@ void Sequence::Active::next()
me = weak_from_this(),
event_index_plus_one = _current_event_index_plus_one
]()
{
if (const auto self = me.lock())
{
if (const auto self = me.lock())
{
if (event_index_plus_one == self->_current_event_index_plus_one)
self->next();
}
};
if (event_index_plus_one == self->_current_event_index_plus_one)
self->next();
}
};

_current = next_event->begin(_checkpoint, event_finished);
} while (_current->state()->finished());
Expand Down
8 changes: 4 additions & 4 deletions rmf_task_sequence/test/unit/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,10 +107,10 @@ std::shared_ptr<rmf_task::Parameters> make_test_parameters(
REQUIRE(graph.num_waypoints() == 13);

auto add_bidir_lane = [&](const std::size_t w0, const std::size_t w1)
{
graph.add_lane(w0, w1);
graph.add_lane(w1, w0);
};
{
graph.add_lane(w0, w1);
graph.add_lane(w1, w0);
};

add_bidir_lane(0, 1);
add_bidir_lane(1, 2);
Expand Down

0 comments on commit fedd853

Please sign in to comment.