Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Event based lift / door logic #320

Merged
merged 5 commits into from
May 10, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 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,7 @@ const std::string DoorSupervisorRequesterID = "door_supervisor";
Node::Node()
: rclcpp::Node("door_supervisor")
{
const auto default_qos = rclcpp::SystemDefaultsQoS();
const auto default_qos = rclcpp::SystemDefaultsQoS().keep_last(100).reliable();
luca-della-vedova marked this conversation as resolved.
Show resolved Hide resolved

_door_request_pub = create_publisher<DoorRequest>(
FinalDoorRequestTopicName, default_qos);
Expand Down
9 changes: 6 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,7 @@ namespace lift_supervisor {
Node::Node()
: rclcpp::Node("rmf_lift_supervisor")
{
const auto default_qos = rclcpp::SystemDefaultsQoS();
const auto default_qos = rclcpp::SystemDefaultsQoS().keep_last(100).reliable();
const auto transient_qos = rclcpp::SystemDefaultsQoS()
.reliable().keep_last(100).transient_local();

Expand Down Expand Up @@ -68,12 +68,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 +87,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 @@ -1046,6 +1046,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
Loading