Skip to content
This repository was archived by the owner on Jul 22, 2021. It is now read-only.
Draft
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
3 changes: 3 additions & 0 deletions rmf_fleet_adapter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ set(dep_pkgs
rmf_traffic_ros2
rmf_battery
rmf_task
rmf_task_ros2
std_msgs
)
foreach(pkg ${dep_pkgs})
Expand All @@ -62,6 +63,7 @@ target_link_libraries(rmf_fleet_adapter
rmf_traffic_ros2::rmf_traffic_ros2
rmf_battery::rmf_battery
rmf_task::rmf_task
rmf_task_ros2::rmf_task_ros2
yaml-cpp
${rmf_fleet_msgs_LIBRARIES}
${rclcpp_LIBRARIES}
Expand Down Expand Up @@ -322,6 +324,7 @@ target_include_directories(task_aggregator
ament_export_targets(rmf_fleet_adapter HAS_LIBRARY_TARGET)
ament_export_dependencies(
rmf_task
rmf_task_ros2
rmf_traffic_ros2
rmf_fleet_msgs
rmf_door_msgs
Expand Down
6 changes: 0 additions & 6 deletions rmf_fleet_adapter/include/rmf_fleet_adapter/StandardNames.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,12 +49,6 @@ const std::string IngestorStateTopicName = "ingestor_states";
const std::string DeliveryTopicName = "delivery_requests";
const std::string LoopRequestTopicName = "loop_requests";
const std::string TaskSummaryTopicName = "task_summaries";

const std::string BidNoticeTopicName = "rmf_task/bid_notice";
const std::string BidProposalTopicName = "rmf_task/bid_proposal";
const std::string DispatchRequestTopicName = "rmf_task/dispatch_request";
const std::string DispatchAckTopicName = "rmf_task/dispatch_ack";

const std::string DockSummaryTopicName = "dock_summary";

} // namespace rmf_fleet_adapter
Expand Down
2 changes: 1 addition & 1 deletion rmf_fleet_adapter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<depend>rmf_traffic_msgs</depend>
<depend>rmf_battery</depend>
<depend>rmf_task</depend>
<depend>rmf_task_ros2</depend>

<build_depend>eigen</build_depend>
<build_depend>yaml-cpp</build_depend>
Expand All @@ -34,4 +35,3 @@
<build_type>ament_cmake</build_type>
</export>
</package>

2 changes: 0 additions & 2 deletions rmf_fleet_adapter/src/full_control/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -670,8 +670,6 @@ std::shared_ptr<Connections> make_fleet(
if (node->declare_parameter<bool>("perform_deliveries", false))
{
task_types.insert(rmf_task_msgs::msg::TaskType::TYPE_DELIVERY);
connections->fleet->accept_delivery_requests(
[](const rmf_task_msgs::msg::Delivery&){ return true; });
}

if (node->declare_parameter<bool>("perform_cleaning", false))
Expand Down
12 changes: 12 additions & 0 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/Task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,18 @@ const std::string& Task::id() const
return _id;
}

//==============================================================================
const rmf_task_msgs::msg::TaskProfile Task::profile_msg() const
{
return _profile_msg;
}

//==============================================================================
void Task::profile_msg(const rmf_task_msgs::msg::TaskProfile& profile)
{
_profile_msg = profile;
}

//==============================================================================
const rmf_task::ConstRequestPtr Task::request() const
{
Expand Down
8 changes: 8 additions & 0 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/Task.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ class Task : public std::enable_shared_from_this<Task>
public:

using StatusMsg = rmf_task_msgs::msg::TaskSummary;
using TaskProfile = rmf_task_msgs::msg::TaskProfile;

/// This class represents the active phase of a Task. It provides an
/// observable that the Task can track to stay up-to-date on the status and to
Expand Down Expand Up @@ -123,6 +124,12 @@ class Task : public std::enable_shared_from_this<Task>
void cancel();

const std::string& id() const;

/// Get the profile msg, for publish status msg
const TaskProfile profile_msg() const;

/// Set the profile msg, for publish status msg
void profile_msg(const TaskProfile& profile);

/// Get the request used to generate this task
const rmf_task::ConstRequestPtr request() const;
Expand Down Expand Up @@ -162,6 +169,7 @@ class Task : public std::enable_shared_from_this<Task>
rmf_traffic::Time _deployment_time;
rmf_task::agv::State _finish_state;
rmf_task::ConstRequestPtr _request;
TaskProfile _profile_msg;

void _start_next_phase();

Expand Down
Loading