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

Remove dependency on rmf_dispenser_msgs #36

Merged
merged 2 commits into from
Aug 18, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
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
7 changes: 1 addition & 6 deletions rmf_task/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@ include(GNUInstallDirs)
find_package(rmf_utils REQUIRED)
find_package(rmf_traffic REQUIRED)
find_package(rmf_battery REQUIRED)
find_package(rmf_dispenser_msgs REQUIRED)
find_package(Eigen3 REQUIRED)

find_package(ament_cmake_catch2 QUIET)
Expand All @@ -43,15 +42,13 @@ add_library(rmf_task SHARED
target_link_libraries(rmf_task
PUBLIC
rmf_battery::rmf_battery
${rmf_dispenser_msgs_LIBRARIES}
)

target_include_directories(rmf_task
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:${CMAKE_INSTALL_INCLUDEDIR}>
${EIGEN3_INCLUDE_DIRS}
${rmf_dispenser_msgs_INCLUDE_DIRS}
)

if(BUILD_TESTING AND ament_cmake_catch2_FOUND AND rmf_cmake_uncrustify_FOUND)
Expand All @@ -64,16 +61,14 @@ if(BUILD_TESTING AND ament_cmake_catch2_FOUND AND rmf_cmake_uncrustify_FOUND)
rmf_task
rmf_utils::rmf_utils
rmf_traffic::rmf_traffic
${rmf_dispenser_msgs_LIBRARIES}
)

target_include_directories(test_rmf_task
PRIVATE
$<BUILD_INTERFACE:${CMAKE_CURRENT_LIST_DIR}/>
${rmf_dispenser_msgs_INCLUDE_DIRS}
)

find_file(uncrustify_config_file
find_file(uncrustify_config_file
NAMES "rmf_code_style.cfg"
PATHS "${rmf_utils_DIR}/../../../share/rmf_utils/")

Expand Down
25 changes: 8 additions & 17 deletions rmf_task/include/rmf_task/requests/Delivery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,6 @@
#include <rmf_task/Request.hpp>
#include <rmf_task/Estimate.hpp>

#include <rmf_dispenser_msgs/msg/dispenser_request_item.hpp>

namespace rmf_task {
namespace requests {

Expand All @@ -48,15 +46,13 @@ class Delivery
{
public:

using DispenserRequestItem = rmf_dispenser_msgs::msg::DispenserRequestItem;
using Start = rmf_traffic::agv::Planner::Start;

static DescriptionPtr make(
std::size_t pickup_waypoint,
std::string pickup_dispenser,
rmf_traffic::Duration pickup_duration,
std::size_t dropoff_waypoint,
std::string dropoff_ingestor,
std::vector<DispenserRequestItem> items);
rmf_traffic::Duration dropoff_duration);

std::shared_ptr<Request::Model> make_model(
rmf_traffic::Time earliest_start_time,
Expand All @@ -65,32 +61,27 @@ class Delivery
/// Get the pickup waypoint in this request
std::size_t pickup_waypoint() const;

/// Get the name of the dispenser at the pickup waypoint
const std::string& pickup_dispenser() const;
/// Get the duration over which delivery items are loaded
rmf_traffic::Duration pickup_wait() const;

/// Get the dropoff waypoint in this request
std::size_t dropoff_waypoint() const;

/// Get the name of the ingestor at the dropoff waypoint
const std::string& dropoff_ingestor() const;

/// Get the list of dispenser request items in this request
const std::vector<DispenserRequestItem>& items() const;
/// Get the duration over which delivery items are unloaded
rmf_traffic::Duration dropoff_wait() const;

class Implementation;
private:
Description();
rmf_utils::impl_ptr<Implementation> _pimpl;
};

using DispenserRequestItem = rmf_dispenser_msgs::msg::DispenserRequestItem;

static ConstRequestPtr make(
std::size_t pickup_waypoint,
std::string pickup_dispenser,
rmf_traffic::Duration pickup_wait,
std::size_t dropoff_waypoint,
std::string dropoff_ingestor,
std::vector<DispenserRequestItem> items,
rmf_traffic::Duration dropoff_wait,
const std::string& id,
rmf_traffic::Time earliest_start_time,
ConstPriorityPtr priority = nullptr);
Expand Down
1 change: 0 additions & 1 deletion rmf_task/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@

<depend>rmf_battery</depend>
<depend>rmf_utils</depend>
<depend>rmf_dispenser_msgs</depend>

<depend>eigen</depend>

Expand Down
60 changes: 29 additions & 31 deletions rmf_task/src/rmf_task/requests/Delivery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,13 +38,17 @@ class Delivery::Model : public Request::Model
const rmf_traffic::Time earliest_start_time,
const agv::Parameters& parameters,
std::size_t pickup_waypoint,
std::size_t dropoff_waypoint);
rmf_traffic::Duration pickup_wait,
std::size_t dropoff_waypoint,
rmf_traffic::Duration dropoff_wait);

private:
rmf_traffic::Time _earliest_start_time;
agv::Parameters _parameters;
std::size_t _pickup_waypoint;
rmf_traffic::Duration _pickup_wait;
std::size_t _dropoff_waypoint;
rmf_traffic::Duration _dropoff_wait;

rmf_traffic::Duration _invariant_duration;
double _invariant_battery_drain;
Expand All @@ -55,15 +59,19 @@ Delivery::Model::Model(
const rmf_traffic::Time earliest_start_time,
const agv::Parameters& parameters,
std::size_t pickup_waypoint,
std::size_t dropoff_waypoint)
rmf_traffic::Duration pickup_wait,
std::size_t dropoff_waypoint,
rmf_traffic::Duration dropoff_wait)
: _earliest_start_time(earliest_start_time),
_parameters(parameters),
_pickup_waypoint(pickup_waypoint),
_dropoff_waypoint(dropoff_waypoint)
{
// Calculate duration of invariant component of task
_invariant_duration = rmf_traffic::Duration{0};
_invariant_battery_drain = 0.0;
_invariant_duration = pickup_wait + dropoff_wait;
_invariant_battery_drain =
_parameters.ambient_sink()->compute_change_in_charge(
rmf_traffic::time::to_seconds(pickup_wait + dropoff_wait));

if (_pickup_waypoint != _dropoff_waypoint)
{
Expand Down Expand Up @@ -276,26 +284,23 @@ class Delivery::Description::Implementation
{}

std::size_t pickup_waypoint;
std::string pickup_dispenser;
rmf_traffic::Duration pickup_wait;
std::size_t dropoff_waypoint;
std::string dropoff_ingestor;
std::vector<DispenserRequestItem> items;
rmf_traffic::Duration dropoff_wait;
};

//==============================================================================
rmf_task::DescriptionPtr Delivery::Description::make(
std::size_t pickup_waypoint,
std::string pickup_dispenser,
rmf_traffic::Duration pickup_wait,
std::size_t dropoff_waypoint,
std::string dropoff_ingestor,
std::vector<DispenserRequestItem> items)
rmf_traffic::Duration dropoff_wait)
{
std::shared_ptr<Description> delivery(new Description());
delivery->_pimpl->pickup_waypoint = pickup_waypoint;
delivery->_pimpl->pickup_dispenser = std::move(pickup_dispenser);
delivery->_pimpl->pickup_wait = pickup_wait;
delivery->_pimpl->dropoff_waypoint = dropoff_waypoint;
delivery->_pimpl->dropoff_ingestor = std::move(dropoff_ingestor);
delivery->_pimpl->items = std::move(items);
delivery->_pimpl->dropoff_wait = dropoff_wait;

return delivery;
}
Expand All @@ -316,7 +321,9 @@ std::shared_ptr<Request::Model> Delivery::Description::make_model(
earliest_start_time,
parameters,
_pimpl->pickup_waypoint,
_pimpl->dropoff_waypoint);
_pimpl->pickup_wait,
_pimpl->dropoff_waypoint,
_pimpl->dropoff_wait);
}

//==============================================================================
Expand All @@ -326,15 +333,15 @@ std::size_t Delivery::Description::pickup_waypoint() const
}

//==============================================================================
const std::string& Delivery::Description::pickup_dispenser() const
rmf_traffic::Duration Delivery::Description::pickup_wait() const
{
return _pimpl->pickup_dispenser;
return _pimpl->pickup_wait;
}

//==============================================================================
const std::string& Delivery::Description::dropoff_ingestor() const
rmf_traffic::Duration Delivery::Description::dropoff_wait() const
{
return _pimpl->dropoff_ingestor;
return _pimpl->dropoff_wait;
}

//==============================================================================
Expand All @@ -343,30 +350,21 @@ std::size_t Delivery::Description::dropoff_waypoint() const
return _pimpl->dropoff_waypoint;
}

//==============================================================================
const std::vector<Delivery::Description::DispenserRequestItem>&
Delivery::Description::items() const
{
return _pimpl->items;
}

//==============================================================================
ConstRequestPtr Delivery::make(
std::size_t pickup_waypoint,
std::string pickup_dispenser,
rmf_traffic::Duration pickup_wait,
std::size_t dropoff_waypoint,
std::string dropoff_ingestor,
std::vector<DispenserRequestItem> items,
rmf_traffic::Duration dropoff_wait,
const std::string& id,
rmf_traffic::Time earliest_start_time,
ConstPriorityPtr priority)
{
const auto description = Description::make(
pickup_waypoint,
pickup_dispenser,
pickup_wait,
dropoff_waypoint,
dropoff_ingestor,
items);
dropoff_wait);

return std::make_shared<Request>(
id, earliest_start_time, std::move(priority), description);
Expand Down
Loading