Class RobotUpdateHandle
Defined in File RobotUpdateHandle.hpp
Nested Relationships
Nested Types
Class Documentation
-
class RobotUpdateHandle
You will be given an instance of this class every time you add a new robot to your fleet. Use that instance to send updates to RoMi-H about your robot’s state.
Public Types
-
enum class Tier
Values:
-
enumerator Info
General status information, does not require special attention.
-
enumerator Warning
Something unusual that might require attention.
-
enumerator Error
A critical failure that requires immediate operator attention.
-
enumerator Info
-
using ActivityIdentifierPtr = std::shared_ptr<ActivityIdentifier>
-
using ConstActivityIdentifierPtr = std::shared_ptr<const ActivityIdentifier>
-
using ActionExecutor = std::function<void(const std::string &category, const nlohmann::json &description, ActionExecution execution)>
Signature for a callback to request the robot to perform an action
- Param category:
[in] A category of the action to be performed
- Param description:
[in] A description of the action to be performed
- Param execution:
[in] An ActionExecution object that will be provided to the user for updating the state of the action.
Public Functions
-
void interrupted()
-
void replan()
Tell the RMF schedule that the robot needs a new plan. A new plan will be generated, starting from the last position that was given by update_position(). It is best to call update_position() with the latest position of the robot before calling this function.
-
void update_position(std::size_t waypoint, double orientation)
Update the current position of the robot by specifying the waypoint that the robot is on and its orientation.
-
void update_position(const Eigen::Vector3d &position, const std::vector<std::size_t> &lanes)
Update the current position of the robot by specifying the x, y, yaw position of the robot and one or more lanes that the robot is occupying.
Warning
At least one lane must be specified. If no lane information is available, then use the update_position(std::string, Eigen::Vector3d) signature of this function.
-
void update_position(const Eigen::Vector3d &position, std::size_t target_waypoint)
Update the current position of the robot by specifying the x, y, yaw position of the robot and the waypoint that it is moving towards.
This should be used if the robot has diverged significantly from its course but it is merging back onto a waypoint.
-
void update_position(const std::string &map_name, const Eigen::Vector3d &position, const double max_merge_waypoint_distance = 0.1, const double max_merge_lane_distance = 1.0, const double min_lane_length = 1e-8)
Update the current position of the robot by specifying the x, y, yaw position of the robot and what map the robot is on.
We will attempt to merge the robot back onto the navigation graph. The parameters for this function are passed along to rmf_traffic::agv::compute_plan_starts().
Warning
This function should only be used if the robot has diverged from the navigation graph somehow.
-
void update_position(rmf_traffic::agv::Plan::StartSet position)
Update the current position of the robot by specifying a plan start set for it.
-
RobotUpdateHandle &set_charger_waypoint(const std::size_t charger_wp)
Set the waypoint where the charger for this robot is located. If not specified, the nearest waypoint in the graph with the is_charger() property will be assumed as the charger for this robot.
-
void update_battery_soc(const double battery_soc)
Update the current battery level of the robot by specifying its state of charge as a fraction of its total charge capacity, i.e. a value from 0.0 to 1.0.
-
void override_status(std::optional<std::string> status)
Use this function to override the robot status. The string provided must be a valid enum as specified in the robot_state.json schema. Pass std::nullopt to cancel the override and allow RMF to automatically update the status. The default value is std::nullopt.
-
RobotUpdateHandle &maximum_delay(rmf_utils::optional<rmf_traffic::Duration> value)
Specify how high the delay of the current itinerary can become before it gets interrupted and replanned. A nullopt value will allow for an arbitrarily long delay to build up without being interrupted.
-
rmf_utils::optional<rmf_traffic::Duration> maximum_delay() const
Get the value for the maximum delay.
Note
The setter for the maximum_delay field is run asynchronously, so it may take some time for the return value of this getter to match the value that was given to the setter.
-
const std::string current_task_id() const
Get the current task ID of the robot, or an empty string if the robot is not performing any task.
-
void set_action_executor(ActionExecutor action_executor)
Set the ActionExecutor for this robot.
-
void submit_direct_request(nlohmann::json task_request, std::string request_id, std::function<void(nlohmann::json response)> receive_response)
Submit a direct task request to this manager
- Parameters:
task_request – [in] A JSON description of the task request. It should match the task_request.json schema of rmf_api_msgs, in particular it must contain
category
anddescription
properties.request_id – [in] The unique ID for this task request.
receive_response – [in] Provide a callback to receive the response. The response will be a robot_task_response.json message from rmf_api_msgs (note: this message is not validated before being returned).
-
Interruption interrupt(std::vector<std::string> labels, std::function<void()> robot_is_interrupted)
Interrupt (pause) the current task, yielding control of the robot away from the fleet adapter’s task manager.
- Parameters:
labels – [in] Labels that will be assigned to this interruption. It is recommended to include information about why the interruption is happening.
- Returns:
a handle for this interruption.
-
void cancel_task(std::string task_id, std::vector<std::string> labels, std::function<void(bool task_was_found)> on_cancellation)
Cancel a task, if it has been assigned to this robot
- Parameters:
task_id – [in] The ID of the task to be canceled
labels – [in] Labels that will be assigned to this cancellation. It is recommended to include information about why the cancellation is happening.
on_cancellation – [in] Callback that will be triggered after the cancellation is issued. task_was_found will be true if the task was successfully found and issued the cancellation, false otherwise.
-
void kill_task(std::string task_id, std::vector<std::string> labels, std::function<void(bool task_was_found)> on_kill)
Kill a task, if it has been assigned to this robot
- Parameters:
task_id – [in] The ID of the task to be canceled
labels – [in] Labels that will be assigned to this cancellation. It is recommended to include information about why the cancellation is happening.
on_kill – [in] Callback that will be triggered after the cancellation is issued. task_was_found will be true if the task was successfully found and issued the kill, false otherwise.
-
IssueTicket create_issue(Tier tier, std::string category, nlohmann::json detail)
Create a new issue for the robot.
- Parameters:
tier – [in] The severity of the issue
category – [in] A brief category to describe the issue
detail – [in] Full details of the issue that might be relevant to an operator or logging system.
- Returns:
A ticket for this issue
-
void log_info(std::string text)
Add a log entry with Info severity.
-
void log_warning(std::string text)
Add a log entry with Warning severity.
-
void log_error(std::string text)
Add a log entry with Error severity.
-
void enable_responsive_wait(bool value)
Toggle the responsive wait behavior for this robot. When responsive wait is active, the robot will remain in the traffic schedule when it is idle and will negotiate its position with other traffic participants to potentially move out of their way.
Disabling this behavior may be helpful to reduce CPU load or prevent parked robots from moving or being seen as conflicts when they are not actually at risk of creating traffic conflicts.
By default this behavior is enabled.
-
void release_lift()
If the robot is holding onto a session with a lift, release that session.
-
class ActionExecution
The ActionExecution class should be used to manage the execution of and provide updates on ongoing actions.
Public Functions
-
void update_remaining_time(rmf_traffic::Duration remaining_time_estimate)
Update the amount of time remaining for this action. This does not need to be used for navigation requests.
-
void underway(std::optional<std::string> text)
Set task status to underway and optionally log a message (info tier)
-
void error(std::optional<std::string> text)
Set task status to error and optionally log a message (error tier)
-
void delayed(std::optional<std::string> text)
Set the task status to delayed and optionally log a message (warning tier)
-
void blocked(std::optional<std::string> text)
Set the task status to blocked and optionally log a message (warning tier)
-
Stubbornness override_schedule(std::string map, std::vector<Eigen::Vector3d> path, rmf_traffic::Duration hold = rmf_traffic::Duration(0))
Use this to override the traffic schedule for the agent while it performs this command.
If the given trajectory results in a traffic conflict then a negotiation will be triggered. Hold onto the
Stubbornness
returned by this function to ask other agents to plan around your trajectory, otherwise the negotiation may result in a replan for this agent and a new command will be issued.Note
Using this will function always trigger a replan once the agent finishes the command.
Warning
Too many overridden/stubborn agents can cause a deadlock. It’s recommended to use this API sparingly and only over short distances or small deviations.
- Parameters:
map – [in] Name of the map where the trajectory will take place
path – [in] The path of the agent
hold – [in] How long the agent will wait at the end of the path
- Returns:
a Stubbornness handle that tells the fleet adapter to not let the overridden path be negotiated. The returned handle will stop having an effect after this command execution is finished.
-
void finished()
Trigger this when the action is successfully finished. No other functions in this ActionExecution instance will be usable after this.
-
bool okay() const
Returns false if the Action has been killed or cancelled.
-
ConstActivityIdentifierPtr identifier() const
Activity identifier for this action. Used by the EasyFullControl API.
-
void update_remaining_time(rmf_traffic::Duration remaining_time_estimate)
-
class ActivityIdentifier
Unique identifier for an activity that the robot is performing. Used by the EasyFullControl API.
Public Functions
-
bool operator==(const ActivityIdentifier&) const
Compare whether two activity handles are referring to the same activity.
-
bool operator==(const ActivityIdentifier&) const
-
class Interruption
An object to maintain an interruption of the current task. When this object is destroyed, the task will resume.
Public Functions
-
void resume(std::vector<std::string> labels)
Call this function to resume the task while providing labels for resuming.
-
void resume(std::vector<std::string> labels)
-
class IssueTicket
An object to maintain an issue that is happening with the robot. When this object is destroyed without calling resolve(), the issue will be “dropped”, which issues a warning to the log.
Public Functions
-
void resolve(nlohmann::json msg)
Indicate that the issue has been resolved. The provided message will be logged for this robot and the issue will be removed from the robot state.
-
void resolve(nlohmann::json msg)
-
class Stubbornness
Hold onto this class to tell the robot to behave as a “stubborn
negotiator”, meaning it will always refuse to accommodate the schedule of any other agent. This could be used when teleoperating a robot, to tell other robots that the agent is unable to negotiate.
When the object is destroyed, the stubbornness will automatically be released.
Public Functions
-
void release()
Stop being stubborn.
-
void release()
-
class Unstable
This API is experimental and will not be supported in the future. Users are to avoid relying on these feature for any integration.
Public Types
-
using Stubbornness = RobotUpdateHandle::Stubbornness
-
using Decide = std::function<void(Decision)>
A callback with this signature will be given to the watchdog when the robot is ready to enter a lift. If the watchdog passes in a true, then the robot will proceed to enter the lift. If the watchdog passes in a false, then the fleet adapter will release its session with the lift and resume later.
Public Functions
-
bool is_commissioned() const
True if this robot is allowed to accept new tasks. False if the robot will not accept any new tasks.
-
void decommission()
Stop this robot from accepting any new tasks. It will continue to perform tasks that are already in its queue. To reassign those tasks, you will need to use the task request API to cancel the tasks and re-request them.
-
void recommission()
Allow this robot to resume accepting new tasks.
-
rmf_traffic::schedule::Participant *get_participant()
Get the schedule participant of this robot.
-
void change_participant_profile(double footprint_radius, double vicinity_radius)
Change the radius of the footprint and vicinity of this participant.
-
void declare_holding(std::string on_map, Eigen::Vector3d at_position, rmf_traffic::Duration for_duration = std::chrono::seconds(30))
Override the schedule to say that the robot will be holding at a certain position. This should not be used while tasks with automatic schedule updating are running, or else the traffic schedule will have jumbled up information, which can be disruptive to the overall traffic management.
-
rmf_traffic::PlanId current_plan_id() const
Get the current Plan ID that this robot has sent to the traffic schedule.
-
Stubbornness be_stubborn()
Tell this robot to be a stubborn negotiator.
-
void set_lift_entry_watchdog(Watchdog watchdog, rmf_traffic::Duration wait_duration = std::chrono::seconds(10))
Set a callback that can be used to check whether the robot is clear to enter the lift.
-
void debug_positions(bool on)
Turn on/off a debug dump of how position updates are being processed.
-
using Stubbornness = RobotUpdateHandle::Stubbornness
-
enum class Tier