Skip to content

Commit

Permalink
Mega Re-name
Browse files Browse the repository at this point in the history
As per a discussion with @mxgrey we are avoiding the use of the word
"chope".

Signed-off-by: Arjo Chakravarty <[email protected]>
  • Loading branch information
arjo129 committed Sep 25, 2024
1 parent 704d140 commit 32f2160
Show file tree
Hide file tree
Showing 16 changed files with 144 additions and 146 deletions.
2 changes: 1 addition & 1 deletion rmf_fleet_adapter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
<depend>rmf_api_msgs</depend>
<depend>rmf_battery</depend>
<depend>rmf_building_map_msgs</depend>
<depend>rmf_chope_msgs</depend>
<depend>rmf_reservation_msgs</depend>
<depend>rmf_dispenser_msgs</depend>
<depend>rmf_door_msgs</depend>
<depend>rmf_fleet_msgs</depend>
Expand Down
24 changes: 12 additions & 12 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/agv/Node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@
#include <rmf_lift_msgs/msg/lift_request.hpp>
#include <rmf_lift_msgs/msg/lift_state.hpp>
#include <rmf_task_msgs/msg/task_summary.hpp>
#include <rmf_chope_msgs/msg/flexible_time_request.hpp>
#include <rmf_chope_msgs/msg/claim_request.hpp>
#include <rmf_chope_msgs/msg/ticket.hpp>
#include <rmf_chope_msgs/msg/reservation_allocation.hpp>
#include <rmf_chope_msgs/msg/release_request.hpp>
#include <rmf_chope_msgs/msg/free_parking_spots.hpp>
#include <rmf_reservation_msgs/msg/flexible_time_request.hpp>
#include <rmf_reservation_msgs/msg/claim_request.hpp>
#include <rmf_reservation_msgs/msg/ticket.hpp>
#include <rmf_reservation_msgs/msg/reservation_allocation.hpp>
#include <rmf_reservation_msgs/msg/release_request.hpp>
#include <rmf_reservation_msgs/msg/free_parking_spots.hpp>

#include <std_msgs/msg/bool.hpp>

Expand Down Expand Up @@ -143,30 +143,30 @@ class Node : public rmf_rxcpp::Transport
using MutexGroupStatesObs = rxcpp::observable<MutexGroupStates::SharedPtr>;
const MutexGroupStatesObs& mutex_group_states() const;

using ReservationRequest = rmf_chope_msgs::msg::FlexibleTimeRequest;
using ReservationRequest = rmf_reservation_msgs::msg::FlexibleTimeRequest;
using ReservationRequestPub =
rclcpp::Publisher<ReservationRequest>::SharedPtr;
const ReservationRequestPub& location_requester() const;

using ReservationTicket = rmf_chope_msgs::msg::Ticket;
using ReservationTicket = rmf_reservation_msgs::msg::Ticket;
using ReservationTicketObs = rxcpp::observable<ReservationTicket::SharedPtr>;
const ReservationTicketObs& location_ticket_obs() const;

using ReservationClaim = rmf_chope_msgs::msg::ClaimRequest;
using ReservationClaim = rmf_reservation_msgs::msg::ClaimRequest;
using ReservationClaimPub = rclcpp::Publisher<ReservationClaim>::SharedPtr;
const ReservationClaimPub& claim_location_ticket() const;

using ReservationAllocation = rmf_chope_msgs::msg::ReservationAllocation;
using ReservationAllocation = rmf_reservation_msgs::msg::ReservationAllocation;
using ReservationAllocationObs =
rxcpp::observable<ReservationAllocation::SharedPtr>;
const ReservationAllocationObs& allocated_claims_obs() const;

using ReservationRelease = rmf_chope_msgs::msg::ReleaseRequest;
using ReservationRelease = rmf_reservation_msgs::msg::ReleaseRequest;
using ReservationReleasePub =
rclcpp::Publisher<ReservationRelease>::SharedPtr;
const ReservationReleasePub& release_location() const;

using ReservationFreeSpotStatus = rmf_chope_msgs::msg::FreeParkingSpots;
using ReservationFreeSpotStatus = rmf_reservation_msgs::msg::FreeParkingSpots;
using ReservationFreeSpotObs =
rxcpp::observable<ReservationFreeSpotStatus::SharedPtr>;
const ReservationFreeSpotObs& freespots_obs() const;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#define SRC__RMF_FLEET_ADAPTER__AGV__RESERVATION_MANAGER_HPP
#include <deque>
#include <optional>
#include <rmf_chope_msgs/msg/reservation_allocation.hpp>
#include <rmf_reservation_msgs/msg/reservation_allocation.hpp>

namespace rmf_fleet_adapter {
namespace agv {
Expand All @@ -28,12 +28,12 @@ namespace agv {
class ReservationManager
{
public:
void add_ticket(const rmf_chope_msgs::msg::ReservationAllocation alloc)
void add_ticket(const rmf_reservation_msgs::msg::ReservationAllocation alloc)
{
allocations.push_front(alloc);
}

std::optional<rmf_chope_msgs::msg::ReservationAllocation> release_ticket()
std::optional<rmf_reservation_msgs::msg::ReservationAllocation> release_ticket()
{
if (allocations.size() <= 1)
{
Expand All @@ -50,7 +50,7 @@ class ReservationManager
return allocations.size() != 0;
}

std::deque<rmf_chope_msgs::msg::ReservationAllocation> allocations;
std::deque<rmf_reservation_msgs::msg::ReservationAllocation> allocations;
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/agv/RobotContext.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1732,7 +1732,7 @@ void RobotContext::_publish_mutex_group_requests()

//==============================================================================
void RobotContext::_set_allocated_destination(
const rmf_chope_msgs::msg::ReservationAllocation& ticket)
const rmf_reservation_msgs::msg::ReservationAllocation& ticket)
{
_reservation_mgr.add_ticket(ticket);
}
Expand All @@ -1750,7 +1750,7 @@ bool RobotContext::_parking_spot_manager_enabled()
}

//==============================================================================
std::optional<rmf_chope_msgs::msg::ReservationAllocation>
std::optional<rmf_reservation_msgs::msg::ReservationAllocation>
RobotContext::_release_resource()
{
return _reservation_mgr.release_ticket();
Expand Down
4 changes: 2 additions & 2 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/agv/RobotContext.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -757,7 +757,7 @@ class RobotContext

/// Set an allocated destination.
void _set_allocated_destination(
const rmf_chope_msgs::msg::ReservationAllocation&);
const rmf_reservation_msgs::msg::ReservationAllocation&);

/// Set if the parking spot manager is used or not
void _set_parking_spot_manager(const bool enabled);
Expand All @@ -772,7 +772,7 @@ class RobotContext
bool _parking_spot_manager_enabled();

/// Release last resource that was acquired.
std::optional<rmf_chope_msgs::msg::ReservationAllocation> _release_resource();
std::optional<rmf_reservation_msgs::msg::ReservationAllocation> _release_resource();

/// Has ticket now
bool _has_ticket() const;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -167,15 +167,15 @@ auto EmergencyPullover::Active::make(
}
else
{
// Use chope node to retrieve the best emergency location.
// Use reservation node to retrieve the best emergency location.
active->_chosen_goal = std::nullopt;

const auto potential_waitpoints =
active->_context->_find_and_sort_parking_spots(true);

RCLCPP_INFO(active->_context->node()->get_logger(),
"Creating Chope negotiator");
active->_chope_client = chope::ChopeNodeNegotiator::make(
"Creating reservation negotiator");
active->_reservation_client = reservation::reservationNodeNegotiator::make(
active->_context,
potential_waitpoints,
true,
Expand Down Expand Up @@ -265,7 +265,7 @@ void EmergencyPullover::Active::cancel()
_state->update_log().info("Received signal to cancel");
if (_context->_parking_spot_manager_enabled())
{
_chope_client->force_release();
_reservation_client->force_release();
}
_finished();
}
Expand All @@ -278,7 +278,7 @@ void EmergencyPullover::Active::kill()
_state->update_log().info("Received signal to kill");
if (_context->_parking_spot_manager_enabled())
{
_chope_client->force_release();
_reservation_client->force_release();
}
_finished();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include "../services/FindEmergencyPullover.hpp"
#include "../services/FindPath.hpp"
#include "internal_ChopeNegotiator.hpp"
#include "internal_ReservationNegotiator.hpp"


#include "ExecutePlan.hpp"
Expand Down Expand Up @@ -129,7 +129,7 @@ class EmergencyPullover : public rmf_task_sequence::Event
rclcpp::TimerBase::SharedPtr _find_path_timeout;
std::optional<rmf_traffic::agv::Plan::Goal> _chosen_goal;

std::shared_ptr<chope::ChopeNodeNegotiator> _chope_client;
std::shared_ptr<reservation::reservationNodeNegotiator> _reservation_client;

bool _is_interrupted = false;
};
Expand Down
30 changes: 15 additions & 15 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/events/GoToPlace.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "GoToPlace.hpp"
#include "../project_itinerary.hpp"
#include "internal_ChopeNegotiator.hpp"
#include "internal_ReservationNegotiator.hpp"
#include "internal_Utilities.hpp"
#include "PerformAction.hpp"

Expand Down Expand Up @@ -286,8 +286,8 @@ auto GoToPlace::Active::make(
active->_chosen_goal = std::nullopt;

RCLCPP_INFO(active->_context->node()->get_logger(),
"Creating Chope negotiator");
active->_chope_client = std::move(chope::ChopeNodeNegotiator::make(
"Creating reservation negotiator");
active->_reservation_client = std::move(reservation::reservationNodeNegotiator::make(
active->_context,
active->_description.one_of(),
active->_description.prefer_same_map(),
Expand All @@ -296,15 +296,15 @@ auto GoToPlace::Active::make(
{
if (auto self = w.lock())
{
self->_on_chope_node_allocate_final_destination(goal);
self->_on_reservation_node_allocate_final_destination(goal);
}
},
[w =
active->weak_from_this()](const rmf_traffic::agv::Plan::Goal& goal)
{
if (auto self = w.lock())
{
self->_on_chope_node_allocate_waitpoint(goal);
self->_on_reservation_node_allocate_waitpoint(goal);
}
}
));
Expand All @@ -320,11 +320,11 @@ auto GoToPlace::Active::state() const -> ConstStatePtr
}

//==============================================================================
void GoToPlace::Active::_on_chope_node_allocate_final_destination(
void GoToPlace::Active::_on_reservation_node_allocate_final_destination(
const rmf_traffic::agv::Plan::Goal& goal)
{
RCLCPP_INFO(_context->node()->get_logger(),
"%s Received final destination %s from chope node",
"%s Received final destination %s from reservation node",
_context->requester_id().c_str(),
wp_name(*_context, goal).c_str());
_is_final_destination = true;
Expand All @@ -334,11 +334,11 @@ void GoToPlace::Active::_on_chope_node_allocate_final_destination(
}

//==============================================================================
void GoToPlace::Active::_on_chope_node_allocate_waitpoint(
void GoToPlace::Active::_on_reservation_node_allocate_waitpoint(
const rmf_traffic::agv::Plan::Goal& goal)
{
RCLCPP_INFO(_context->node()->get_logger(),
"Received waitpoint from chope node");
"Received waitpoint from reservation node");
_chosen_goal = goal;
_find_plan();
}
Expand Down Expand Up @@ -433,7 +433,7 @@ void GoToPlace::Active::cancel()

if (_context->_parking_spot_manager_enabled())
{
_chope_client->force_release();
_reservation_client->force_release();
}
_finished();
}
Expand All @@ -446,7 +446,7 @@ void GoToPlace::Active::kill()
_state->update_log().info("Received signal to kill");
if (_context->_parking_spot_manager_enabled())
{
_chope_client->force_release();
_reservation_client->force_release();
}
_finished();
}
Expand Down Expand Up @@ -478,11 +478,11 @@ std::optional<rmf_traffic::agv::Plan::Goal> GoToPlace::Active::_choose_goal(
if (_context->_parking_spot_manager_enabled())
{
RCLCPP_INFO(_context->node()->get_logger(),
"Requesting Chope Node For Time To Progress");
"Requesting reservation Node For Time To Progress");
}
else
{
RCLCPP_INFO(_context->node()->get_logger(), "Skipping chope node.");
RCLCPP_INFO(_context->node()->get_logger(), "Skipping reservation node.");
auto lowest_cost = std::numeric_limits<double>::infinity();
std::optional<std::size_t> selected_idx;
for (std::size_t i = 0; i < _description.one_of().size(); ++i)
Expand Down Expand Up @@ -758,7 +758,7 @@ void GoToPlace::Active::_execute_plan(
{
RCLCPP_INFO(
_context->node()->get_logger(),
"Chope: Finished execution");
"reservation: Finished execution");
_stop_and_clear();
_finished();
}, _tail_period);
Expand All @@ -772,7 +772,7 @@ void GoToPlace::Active::_execute_plan(
{
RCLCPP_INFO(
_context->node()->get_logger(),
"Chope: Reached waitpoint");
"reservation: Reached waitpoint");

_reached_waitpoint = true;
}, _tail_period);
Expand Down
8 changes: 4 additions & 4 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/events/GoToPlace.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "../services/FindPath.hpp"

#include "ExecutePlan.hpp"
#include "internal_ChopeNegotiator.hpp"
#include "internal_ReservationNegotiator.hpp"

#include <cstdint>
#include <optional>
Expand Down Expand Up @@ -126,10 +126,10 @@ class GoToPlace : public rmf_task_sequence::Event

void _stop_and_clear();

void _on_chope_node_allocate_final_destination(
void _on_reservation_node_allocate_final_destination(
const rmf_traffic::agv::Plan::Goal& goal);

void _on_chope_node_allocate_waitpoint(
void _on_reservation_node_allocate_waitpoint(
const rmf_traffic::agv::Plan::Goal& goal);

Negotiator::NegotiatePtr _respond(
Expand All @@ -154,7 +154,7 @@ class GoToPlace : public rmf_task_sequence::Event
rmf_rxcpp::subscription_guard _replan_request_subscription;
rmf_rxcpp::subscription_guard _graph_change_subscription;

std::shared_ptr<chope::ChopeNodeNegotiator> _chope_client;
std::shared_ptr<reservation::reservationNodeNegotiator> _reservation_client;

bool _is_interrupted = false;
bool _is_final_destination = true;
Expand Down
Loading

0 comments on commit 32f2160

Please sign in to comment.