Skip to content
This repository was archived by the owner on Jul 22, 2021. It is now read-only.
Merged
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
63 changes: 30 additions & 33 deletions rmf_fleet_adapter/src/rmf_fleet_adapter/TaskManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,10 +155,12 @@ void TaskManager::set_queue(
if (i != 0)
start = assignments[i-1].state().location();
start.time(a.deployment_time());
rmf_task_msgs::msg::TaskType task_type_msg;

if (const auto request =
std::dynamic_pointer_cast<const rmf_task::requests::Clean>(a.request()))
{
task_type_msg.type = task_type_msg.TYPE_CLEAN;
auto task = rmf_fleet_adapter::tasks::make_clean(
request,
_context,
Expand All @@ -169,19 +171,13 @@ void TaskManager::set_queue(
std::lock_guard<std::mutex> guard(_mutex);

_queue.push_back(task);

rmf_task_msgs::msg::TaskSummary msg;
msg.task_id = _queue.back()->id();
msg.task_profile.task_id = _queue.back()->id();
msg.state = msg.STATE_QUEUED;
msg.robot_name = _context->name();
this->_context->node()->task_summary()->publish(msg);
}

else if (const auto request =
std::dynamic_pointer_cast<const rmf_task::requests::ChargeBattery>(
a.request()))
{
task_type_msg.type = task_type_msg.TYPE_CHARGE_BATTERY;
const auto task = tasks::make_charge_battery(
request,
_context,
Expand All @@ -192,20 +188,13 @@ void TaskManager::set_queue(
std::lock_guard<std::mutex> guard(_mutex);

_queue.push_back(task);

rmf_task_msgs::msg::TaskSummary msg;
msg.task_id = _queue.back()->id();
msg.task_profile.task_id = _queue.back()->id();
msg.state = msg.STATE_QUEUED;
msg.robot_name = _context->name();
this->_context->node()->task_summary()->publish(msg);

}

else if (const auto request =
std::dynamic_pointer_cast<const rmf_task::requests::Delivery>(
a.request()))
{
task_type_msg.type = task_type_msg.TYPE_DELIVERY;
const auto task = tasks::make_delivery(
request,
_context,
Expand All @@ -214,19 +203,12 @@ void TaskManager::set_queue(
a.state());

_queue.push_back(task);

rmf_task_msgs::msg::TaskSummary msg;
msg.task_id = _queue.back()->id();
msg.task_profile.task_id = _queue.back()->id();
msg.state = msg.STATE_QUEUED;
msg.robot_name = _context->name();
this->_context->node()->task_summary()->publish(msg);

}

else if (const auto request =
std::dynamic_pointer_cast<const rmf_task::requests::Loop>(a.request()))
{
task_type_msg.type = task_type_msg.TYPE_LOOP;
const auto task = tasks::make_loop(
request,
_context,
Expand All @@ -235,19 +217,25 @@ void TaskManager::set_queue(
a.state());

_queue.push_back(task);

rmf_task_msgs::msg::TaskSummary msg;
msg.task_id = _queue.back()->id();
msg.task_profile.task_id = _queue.back()->id();
msg.state = msg.STATE_QUEUED;
msg.robot_name = _context->name();
this->_context->node()->task_summary()->publish(msg);
}

else
{
continue;
}

// publish queued task
rmf_task_msgs::msg::TaskSummary msg;
msg.task_id = _queue.back()->id();
msg.task_profile.task_id = _queue.back()->id();
msg.state = msg.STATE_QUEUED;
msg.robot_name = _context->name();
msg.task_profile.task_type = task_type_msg;
msg.start_time = rmf_traffic_ros2::convert(
_queue.back()->deployment_time());
msg.start_time = rmf_traffic_ros2::convert(
_queue.back()->finish_state().finish_time());
this->_context->node()->task_summary()->publish(msg);
}
}

Expand All @@ -261,11 +249,8 @@ const std::vector<rmf_task::ConstRequestPtr> TaskManager::requests() const
if (std::dynamic_pointer_cast<const rmf_task::requests::ChargeBattery>(
task->request()))
continue;

requests.push_back(task->request());

}

return requests;
}

Expand Down Expand Up @@ -315,6 +300,10 @@ void TaskManager::_begin_next_task()
msg.task_id = id;
msg.task_profile.task_id = id;
msg.robot_name = _context->name();
msg.start_time = rmf_traffic_ros2::convert(
_active_task->deployment_time());
msg.end_time = rmf_traffic_ros2::convert(
_active_task->finish_state().finish_time());
_context->node()->task_summary()->publish(msg);
},
[this, id = _active_task->id()](std::exception_ptr e)
Expand All @@ -332,6 +321,10 @@ void TaskManager::_begin_next_task()
msg.task_id = id;
msg.task_profile.task_id = id;
msg.robot_name = _context->name();
msg.start_time = rmf_traffic_ros2::convert(
_active_task->deployment_time());
msg.end_time = rmf_traffic_ros2::convert(
_active_task->finish_state().finish_time());
_context->node()->task_summary()->publish(msg);
// _begin_next_task();
},
Expand All @@ -342,6 +335,10 @@ void TaskManager::_begin_next_task()
msg.task_profile.task_id = id;
msg.state = msg.STATE_COMPLETED;
msg.robot_name = _context->name();
msg.start_time = rmf_traffic_ros2::convert(
_active_task->deployment_time());
msg.end_time = rmf_traffic_ros2::convert(
_active_task->finish_state().finish_time());
this->_context->node()->task_summary()->publish(msg);

_active_task = nullptr;
Expand Down