Skip to content

Commit

Permalink
Event based lift / door logic (#320)
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <[email protected]>
  • Loading branch information
luca-della-vedova authored May 10, 2024
1 parent 2d35a19 commit 5e58af9
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 4 deletions.
3 changes: 2 additions & 1 deletion rmf_fleet_adapter/src/door_supervisor/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,8 @@ const std::string DoorSupervisorRequesterID = "door_supervisor";
Node::Node()
: rclcpp::Node("door_supervisor")
{
const auto default_qos = rclcpp::SystemDefaultsQoS().keep_last(10);
const auto default_qos =
rclcpp::SystemDefaultsQoS().durability_volatile().keep_last(100).reliable();

_door_request_pub = create_publisher<DoorRequest>(
FinalDoorRequestTopicName, default_qos);
Expand Down
10 changes: 7 additions & 3 deletions rmf_fleet_adapter/src/lift_supervisor/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ namespace lift_supervisor {
Node::Node()
: rclcpp::Node("rmf_lift_supervisor")
{
const auto default_qos = rclcpp::SystemDefaultsQoS().keep_last(10);
const auto default_qos =
rclcpp::SystemDefaultsQoS().durability_volatile().keep_last(100).reliable();
const auto transient_qos = rclcpp::SystemDefaultsQoS()
.reliable().keep_last(100).transient_local();

Expand Down Expand Up @@ -68,12 +69,14 @@ void Node::_adapter_lift_request_update(LiftRequest::UniquePtr msg)
{
if (curr_request->session_id == msg->session_id)
{
msg->request_time = this->now();
_lift_request_pub->publish(*msg);
if (msg->request_type != LiftRequest::REQUEST_END_SESSION)
{
curr_request = std::move(msg);
}
else
{
msg->request_time = this->now();
_lift_request_pub->publish(*msg);
RCLCPP_INFO(
this->get_logger(),
"[%s] Published end lift session from lift supervisor",
Expand All @@ -85,6 +88,7 @@ void Node::_adapter_lift_request_update(LiftRequest::UniquePtr msg)
}
else
{
_lift_request_pub->publish(*msg);
if (msg->request_type != LiftRequest::REQUEST_END_SESSION)
{
curr_request = std::move(msg);
Expand Down
6 changes: 6 additions & 0 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/agv/RobotContext.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1067,6 +1067,12 @@ void RobotContext::release_lift()
"Releasing lift [%s] for [%s]",
_lift_destination->lift_name.c_str(),
requester_id().c_str());
rmf_lift_msgs::msg::LiftRequest msg;
msg.lift_name = _lift_destination->lift_name;
msg.request_type = rmf_lift_msgs::msg::LiftRequest::REQUEST_END_SESSION;
msg.session_id = requester_id();
msg.destination_floor = _lift_destination->destination_floor;
_node->lift_request()->publish(msg);
}
_lift_destination = nullptr;
_initial_time_idle_outside_lift = std::nullopt;
Expand Down

0 comments on commit 5e58af9

Please sign in to comment.