Skip to content
Closed
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
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 @@ -89,6 +89,18 @@ const std::string& Task::id() const
return _id;
}

//==============================================================================
const rmf_task_msgs::msg::TaskProfile Task::task_profile_msg() const
{
return _task_profile_msg;
}

//==============================================================================
void Task::task_profile_msg(const rmf_task_msgs::msg::TaskProfile& profile)
{
_task_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 @@ -124,6 +125,12 @@ class Task : public std::enable_shared_from_this<Task>

const std::string& id() const;

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

/// Set the profile msg, for publish status msg
void task_profile_msg(const TaskProfile& profile);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We can have this function return Task& instead of void


/// 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 _task_profile_msg;

void _start_next_phase();

Expand Down
Loading