Skip to content

Commit f73b541

Browse files
aaronchongthYadunundmxgrey
authored
Adding initiator and request time to booking (#267) (#284)
* Adding initiator and request time to booking * Use new booking and request API for EmergencyPullover and ResponsiveWait * Using new booking and request API for FleetUpdateHandle * Use requester instead of initiator, use new API * requester name for finishing task factories * Using reverted constructors with nullopt default parameters * Fix build failures on build farm (#274) * Fix style for rmf_fleet_adapter * Make colcon test pass for rmf_traffic_ros2 * Add rmf_fleet_adapter_python to build ci --------- * Update changelogs and bump patch (#275) * Switch to rst changelogs (#276) * Put the action finished callback in a schedule instead of triggering immediately (#273) * Put the action finished callback in a schedule instead of triggering immediately * Style * Update CHANGELOG * Move changelog entry into forthcoming --------- * Revert changes to constructing finish request factories * Using overloaded TaskPlanner constructor to pass in name of fleet update handle * Using overloaded rmf_task make functions * Update changelogs * 2.2.0 * Bump 2.3.0 (#282) * Use new booking and request API, updated legacy FullControl fleet adapter * Added node as parameter to pybinded set_task_planner_params, to pass planner_id and time functor to finishing task factory * Using system_clock instead of steady_clock * Remove the need to pass a node into the set_task_planner_params python binding --------- (cherry picked from commit dc740df) Signed-off-by: Aaron Chong <[email protected]> Signed-off-by: Yadunund <[email protected]> Signed-off-by: Yadunund <[email protected]> Signed-off-by: Michael X. Grey <[email protected]> Signed-off-by: Michael X. Grey <[email protected]> Co-authored-by: Yadu <[email protected]> Co-authored-by: Grey <[email protected]> Co-authored-by: Yadunund <[email protected]>
1 parent 48e78cb commit f73b541

File tree

8 files changed

+137
-18
lines changed

8 files changed

+137
-18
lines changed

rmf_fleet_adapter/include/rmf_fleet_adapter/agv/FleetUpdateHandle.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,8 @@
3535
#include <rmf_task_sequence/Phase.hpp>
3636
#include <rmf_task_sequence/Event.hpp>
3737

38+
#include <rclcpp/node.hpp>
39+
3840
namespace rmf_fleet_adapter {
3941
namespace agv {
4042

@@ -367,6 +369,13 @@ class FleetUpdateHandle : public std::enable_shared_from_this<FleetUpdateHandle>
367369
FleetUpdateHandle& set_update_listener(
368370
std::function<void(const nlohmann::json&)> listener);
369371

372+
/// Get the rclcpp::Node that this fleet update handle will be using for
373+
/// communication.
374+
std::shared_ptr<rclcpp::Node> node();
375+
376+
/// const-qualified node()
377+
std::shared_ptr<const rclcpp::Node> node() const;
378+
370379
// Do not allow moving
371380
FleetUpdateHandle(FleetUpdateHandle&&) = delete;
372381
FleetUpdateHandle& operator=(FleetUpdateHandle&&) = delete;

rmf_fleet_adapter/src/full_control/main.cpp

Lines changed: 19 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1234,18 +1234,35 @@ std::shared_ptr<Connections> make_fleet(
12341234
const std::string finishing_request_string =
12351235
node->declare_parameter("finishing_request", "nothing");
12361236
rmf_task::ConstRequestFactoryPtr finishing_request = nullptr;
1237+
std::function<rmf_traffic::Time()> get_time =
1238+
[n = std::weak_ptr<rclcpp::Node>(node)]()
1239+
{
1240+
const auto node = n.lock();
1241+
if (!node)
1242+
{
1243+
const auto time_since_epoch =
1244+
std::chrono::system_clock::now().time_since_epoch();
1245+
return rmf_traffic::Time(time_since_epoch);
1246+
}
1247+
return rmf_traffic_ros2::convert(node->now());
1248+
};
1249+
12371250
if (finishing_request_string == "charge")
12381251
{
12391252
finishing_request =
1240-
std::make_shared<rmf_task::requests::ChargeBatteryFactory>();
1253+
std::make_shared<rmf_task::requests::ChargeBatteryFactory>(
1254+
std::string(node->get_name()),
1255+
std::move(get_time));
12411256
RCLCPP_INFO(
12421257
node->get_logger(),
12431258
"Fleet is configured to perform ChargeBattery as finishing request");
12441259
}
12451260
else if (finishing_request_string == "park")
12461261
{
12471262
finishing_request =
1248-
std::make_shared<rmf_task::requests::ParkRobotFactory>();
1263+
std::make_shared<rmf_task::requests::ParkRobotFactory>(
1264+
std::string(node->get_name()),
1265+
std::move(get_time));
12491266
RCLCPP_INFO(
12501267
node->get_logger(),
12511268
"Fleet is configured to perform ParkRobot as finishing request");

rmf_fleet_adapter/src/rmf_fleet_adapter/TaskManager.cpp

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -421,6 +421,17 @@ void copy_booking_data(
421421
booking_json["id"] = booking.id();
422422
booking_json["unix_millis_earliest_start_time"] =
423423
to_millis(booking.earliest_start_time().time_since_epoch()).count();
424+
const auto requester = booking.requester();
425+
if (requester.has_value())
426+
{
427+
booking_json["requester"] = requester.value();
428+
}
429+
const auto request_time = booking.request_time();
430+
if (request_time.has_value())
431+
{
432+
booking_json["unix_millis_request_time"] =
433+
to_millis(request_time.value().time_since_epoch()).count();
434+
}
424435
// TODO(MXG): Add priority and labels
425436
}
426437

@@ -1576,7 +1587,11 @@ void TaskManager::retreat_to_charger()
15761587
{
15771588
// Add a new charging task to the task queue
15781589
const auto charging_request = rmf_task::requests::ChargeBattery::make(
1579-
current_state.time().value());
1590+
current_state.time().value(),
1591+
_context->requester_id(),
1592+
rmf_traffic_ros2::convert(_context->node()->now()),
1593+
nullptr,
1594+
true);
15801595
const auto model = charging_request->description()->make_model(
15811596
current_state.time().value(),
15821597
parameters);

rmf_fleet_adapter/src/rmf_fleet_adapter/agv/FleetUpdateHandle.cpp

Lines changed: 41 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -238,6 +238,15 @@ std::shared_ptr<rmf_task::Request> FleetUpdateHandle::Implementation::convert(
238238
rmf_traffic::Time(std::chrono::milliseconds(t_it->get<int64_t>()));
239239
}
240240

241+
rmf_traffic::Time request_time = rmf_traffic_ros2::convert(
242+
node->get_clock()->now());
243+
const auto r_it = request_msg.find("unix_millis_request_time");
244+
if (r_it != request_msg.end())
245+
{
246+
request_time =
247+
rmf_traffic::Time(std::chrono::milliseconds(r_it->get<int64_t>()));
248+
}
249+
241250
// Note: make_low_priority() actually returns a nullptr.
242251
rmf_task::ConstPriorityPtr priority =
243252
rmf_task::BinaryPriorityScheme::make_low_priority();
@@ -279,11 +288,28 @@ std::shared_ptr<rmf_task::Request> FleetUpdateHandle::Implementation::convert(
279288
}
280289
}
281290

282-
const auto new_request =
283-
std::make_shared<rmf_task::Request>(
291+
std::optional<std::string> requester = std::nullopt;
292+
const auto i_it = request_msg.find("requester");
293+
if (i_it != request_msg.end())
294+
{
295+
requester = i_it->get<std::string>();
296+
}
297+
298+
rmf_task::Task::ConstBookingPtr booking = requester.has_value() ?
299+
std::make_shared<const rmf_task::Task::Booking>(
300+
task_id,
301+
earliest_start_time,
302+
priority,
303+
requester.value(),
304+
request_time,
305+
false) :
306+
std::make_shared<const rmf_task::Task::Booking>(
284307
task_id,
285308
earliest_start_time,
286309
priority,
310+
false);
311+
const auto new_request = std::make_shared<rmf_task::Request>(
312+
std::move(booking),
287313
deserialized_task.description);
288314

289315
return new_request;
@@ -1995,6 +2021,18 @@ FleetUpdateHandle& FleetUpdateHandle::set_update_listener(
19952021
return *this;
19962022
}
19972023

2024+
//==============================================================================
2025+
std::shared_ptr<rclcpp::Node> FleetUpdateHandle::node()
2026+
{
2027+
return _pimpl->node;
2028+
}
2029+
2030+
//==============================================================================
2031+
std::shared_ptr<const rclcpp::Node> FleetUpdateHandle::node() const
2032+
{
2033+
return _pimpl->node;
2034+
}
2035+
19982036
//==============================================================================
19992037
bool FleetUpdateHandle::set_task_planner_params(
20002038
std::shared_ptr<rmf_battery::agv::BatterySystem> battery_system,
@@ -2044,7 +2082,7 @@ bool FleetUpdateHandle::set_task_planner_params(
20442082
// automatic retreat. Hence, we also update them whenever the
20452083
// task planner here is updated.
20462084
self->_pimpl->task_planner = std::make_shared<rmf_task::TaskPlanner>(
2047-
std::move(task_config), std::move(options));
2085+
self->_pimpl->name, std::move(task_config), std::move(options));
20482086

20492087
for (const auto& t : self->_pimpl->task_managers)
20502088
t.first->task_planner(self->_pimpl->task_planner);

rmf_fleet_adapter/src/rmf_fleet_adapter/events/EmergencyPullover.cpp

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,17 @@ rmf_task::Task::ActivePtr EmergencyPullover::start(
5353
std::make_shared<EmergencyPulloverDescription>()), {});
5454

5555
const auto desc = builder.build("Emergency Pullover", "");
56-
const rmf_task::Request request(task_id, context->now(), nullptr, desc, true);
56+
57+
const auto time_now = context->now();
58+
rmf_task::Task::ConstBookingPtr booking =
59+
std::make_shared<const rmf_task::Task::Booking>(
60+
task_id,
61+
time_now,
62+
nullptr,
63+
context->requester_id(),
64+
time_now,
65+
true);
66+
const rmf_task::Request request(std::move(booking), desc);
5767

5868
return activator.activate(
5969
context->make_get_state(),

rmf_fleet_adapter/src/rmf_fleet_adapter/events/ResponsiveWait.cpp

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,17 @@ rmf_task::Task::ActivePtr ResponsiveWait::start(
7070
ResponsiveWait::Description::make_indefinite(waiting_point)), {});
7171

7272
const auto desc = builder.build("Responsive Wait", "");
73-
const rmf_task::Request request(task_id, context->now(), nullptr, desc, true);
73+
74+
const auto time_now = context->now();
75+
rmf_task::Task::ConstBookingPtr booking =
76+
std::make_shared<const rmf_task::Task::Booking>(
77+
task_id,
78+
time_now,
79+
nullptr,
80+
context->requester_id(),
81+
time_now,
82+
true);
83+
const rmf_task::Request request(std::move(booking), desc);
7484

7585
return context->task_activator()->activate(
7686
context->make_get_state(),

rmf_fleet_adapter_python/src/adapter.cpp

Lines changed: 27 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
#include <pybind11/eigen.h>
55
#include <pybind11/stl.h>
66
#include "pybind11_json/pybind11_json.hpp"
7+
#include <functional>
78
#include <memory>
89

910
#include "rmf_traffic_ros2/Time.hpp"
@@ -333,21 +334,38 @@ PYBIND11_MODULE(rmf_adapter, m) {
333334
bool account_for_battery_drain,
334335
const std::string& finishing_request_string = "nothing")
335336
{
337+
std::function<rmf_traffic::Time()> time_now = nullptr;
338+
std::optional<std::string> planner_id = std::nullopt;
339+
const auto node = self.node();
340+
if (node)
341+
{
342+
time_now = [n = node->weak_from_this()]()
343+
{
344+
const auto node = n.lock();
345+
if (!node)
346+
{
347+
const auto time_since_epoch =
348+
std::chrono::system_clock::now().time_since_epoch();
349+
return rmf_traffic::Time(time_since_epoch);
350+
}
351+
return rmf_traffic_ros2::convert(node->now());
352+
};
353+
planner_id = node->get_name();
354+
}
355+
336356
// Supported finishing_request_string: [charge, park, nothing]
337-
rmf_task::ConstRequestFactoryPtr finishing_request;
357+
rmf_task::ConstRequestFactoryPtr finishing_request = nullptr;
338358
if (finishing_request_string == "charge")
339359
{
340-
finishing_request =
341-
std::make_shared<rmf_task::requests::ChargeBatteryFactory>();
360+
finishing_request = planner_id.has_value() && time_now ?
361+
std::make_shared<rmf_task::requests::ChargeBatteryFactory>(planner_id.value(), std::move(time_now)) :
362+
std::make_shared<rmf_task::requests::ChargeBatteryFactory>();
342363
}
343364
else if (finishing_request_string == "park")
344365
{
345-
finishing_request =
346-
std::make_shared<rmf_task::requests::ParkRobotFactory>();
347-
}
348-
else
349-
{
350-
finishing_request = nullptr;
366+
finishing_request = planner_id.has_value() && time_now ?
367+
std::make_shared<rmf_task::requests::ParkRobotFactory>(planner_id.value(), std::move(time_now)) :
368+
std::make_shared<rmf_task::requests::ParkRobotFactory>();
351369
}
352370

353371
return self.set_task_planner_params(

rmf_task_ros2/src/rmf_task_ros2/Dispatcher.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -800,8 +800,10 @@ class Dispatcher::Implementation
800800

801801
static const std::vector<std::string> copy_fields = {
802802
"unix_millis_earliest_start_time",
803+
"unix_millis_request_time",
803804
"priority",
804-
"labels"
805+
"labels",
806+
"requester",
805807
};
806808

807809
for (const auto& field : copy_fields)

0 commit comments

Comments
 (0)