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

Mutex groups, dynamic charging, and more #310

Merged
merged 100 commits into from
Dec 15, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
100 commits
Select commit Hold shift + click to select a range
cbb6f51
Funnel emergency notifications through the fleet adapter
mxgrey Sep 5, 2023
b917e10
Fix compilation
mxgrey Sep 6, 2023
a8fb88e
Implement emergency lift closing
mxgrey Sep 6, 2023
0768ade
Add API and config file parsing for setting lift emergency level
mxgrey Sep 7, 2023
3ab538c
Fixed and tested fire alarm lift response
mxgrey Sep 12, 2023
2810de5
Provide an explicit hook for localization
mxgrey Sep 20, 2023
6560b44
Fix syntax and add python bindings
mxgrey Sep 20, 2023
1160323
Use CommandExecution with LocalizationRequest
mxgrey Sep 21, 2023
9221f65
Fix segfault
mxgrey Sep 25, 2023
2b5b933
Align the waypoints along each lift shaft
mxgrey Sep 27, 2023
28bb0d4
Merge branch 'fire_alarm_lift_response' of ssh://github.com/open-rmf/…
mxgrey Sep 27, 2023
11ba2a4
Add API to retrieve robot task ID from the RobotUpdateHandle
xiyuoh Sep 25, 2023
2bc79e3
Bug fixes
xiyuoh Sep 28, 2023
5efa1d4
Always move robot location estimates to the bottom of a vertex stack
mxgrey Oct 2, 2023
bd8dc72
Debugging behavior inside of lifts
mxgrey Oct 3, 2023
1a16a6a
Fix infinite loop
mxgrey Oct 3, 2023
ee67443
Only remove lane if descended
mxgrey Oct 4, 2023
25a08b4
Include lift properties in nav graph
mxgrey Oct 4, 2023
bb5ea4f
Remove debug output
mxgrey Oct 5, 2023
3096fd8
Fix pybind
xiyuoh Oct 5, 2023
f280612
Fix arrival estimates
mxgrey Oct 7, 2023
01152bf
Introduction of dynamic charging concept -- WIP
mxgrey Oct 8, 2023
713b57e
Reworking ChargeBattery request + event
mxgrey Oct 10, 2023
bec3145
Making the ChargeBattery event dynamic
mxgrey Oct 11, 2023
c4cbe1d
Change finishing task into idle task
mxgrey Oct 11, 2023
77abe9f
Adding WaitForCancel and introducing a new ParkIndefinitely task
mxgrey Oct 11, 2023
405fe15
Idle tasks runs only once after any active task is finished
mxgrey Oct 12, 2023
c5c35a6
Fix some undefined behavior
mxgrey Oct 12, 2023
fa3fb33
Use global const variable for charging assignments topic name
mxgrey Oct 12, 2023
e6f3557
Introduce a charging schedule management node
mxgrey Oct 12, 2023
27e0aea
Increase lift localize timeout
xiyuoh Oct 14, 2023
9bfe603
Fix cancellation logic for lifts
mxgrey Oct 14, 2023
cc9b921
Adding option to print position update debug info
mxgrey Oct 17, 2023
abef0ca
Change QoS for adapter_lift_requests and lift_requests to transient l…
xiyuoh Oct 18, 2023
4712243
Keep last 100
mxgrey Oct 19, 2023
1e4b479
Change QoS for adapter_lift_requests and lift_requests to transient l…
xiyuoh Oct 19, 2023
01fcb23
Add debug logging to lift supervisor
xiyuoh Oct 23, 2023
5c50376
Adding a mutex group manager
mxgrey Oct 26, 2023
d2e5dfa
Finished implementation of mutex group supervisor -- needs testing
mxgrey Oct 26, 2023
ee8d625
Adding data flows for mutex groups
mxgrey Oct 26, 2023
cbfb50c
merge with lift fixes
mxgrey Oct 26, 2023
2131982
Add context plumbing for mutex groups
mxgrey Oct 26, 2023
b498b3a
Implement LockMutexGroup event -- need to update ExecutePlan
mxgrey Oct 30, 2023
eb242f3
Add mutex group locking and unlocking to ExecutePlan and MoveRobot re…
mxgrey Oct 31, 2023
e8359e1
Release lift when a replan doesn't need the lift anymore
mxgrey Oct 31, 2023
9514a88
Fix mutex for current task ID
mxgrey Oct 31, 2023
8c1e388
fix merge
mxgrey Oct 31, 2023
0018c0d
Identify when an off-vertex location is inside of a lift
mxgrey Nov 1, 2023
45fbd37
Add shared ptr to ActionExecution pybind
xiyuoh Nov 3, 2023
bd0d89b
Release lift from robots that are idle outside of a lift
mxgrey Nov 6, 2023
1def32d
Merge remote-tracking branch 'origin/fix_lift_cancel' into fix_lift_c…
mxgrey Nov 6, 2023
594d5fa
Charging schedule sorting and mid-performaction cancel fixes
xiyuoh Nov 7, 2023
bd7feac
Fix cancellation of WaitForCharge
mxgrey Nov 10, 2023
0d98353
Merge remote-tracking branch 'origin/fix_lift_cancel' into fix_lift_c…
mxgrey Nov 10, 2023
eb93232
Fix merge
mxgrey Nov 12, 2023
40c7a81
Truncate schedule horizons for mutex group changes
mxgrey Nov 12, 2023
50c11c6
Fix shared pointer from prev fix
xiyuoh Nov 14, 2023
74af951
Merge remote-tracking branch 'origin/fix_lift_cancel' into mutex_groups
mxgrey Nov 14, 2023
4956443
Ironing out mutex group behaviors -- need atomic switching
mxgrey Nov 15, 2023
04f1378
Added atomic switching -- need to fix movement continuity bug
mxgrey Nov 15, 2023
dc32398
Fix move_through continuity error
mxgrey Nov 16, 2023
e70f618
Fix atomic switching
mxgrey Nov 16, 2023
7f79231
Ignore traffic dependencies for agents waiting on your locked mutex g…
mxgrey Nov 17, 2023
aa62454
Use mutex group switches as a horizon
mxgrey Nov 20, 2023
5eec5f2
Update to latest API
mxgrey Nov 20, 2023
55c62b1
Fix cases where a mutex group needs to be locked immediately before a…
mxgrey Nov 20, 2023
485d6f3
Lock mutex group before docking when needed
mxgrey Nov 20, 2023
c425b87
Iterating on implementation strategy
mxgrey Nov 21, 2023
9d6f553
Support multiple simultaneous mutex group locks
mxgrey Nov 22, 2023
09b453c
Debug logs and fix speed limit bug
xiyuoh Nov 23, 2023
b960441
More robust decision making for replanning after mutex lock
mxgrey Nov 23, 2023
02f9d6a
More robust lift release
mxgrey Nov 24, 2023
9aebdd2
Merge branch 'fix_door_release' into mutex_groups
mxgrey Nov 24, 2023
6485ffe
More robust door holding and releasing
mxgrey Nov 24, 2023
bcea110
Ensure doors open after an interrupted plan
mxgrey Nov 25, 2023
4d69f2e
Account for waypoint merge radius when dealing with stacked waypoints
mxgrey Nov 25, 2023
4921246
Fix mutex group decay
mxgrey Nov 25, 2023
4e3b4f8
Fix follow_new_path start identification
mxgrey Nov 26, 2023
058b3aa
Fix segfault during door/lift phases
mxgrey Nov 26, 2023
159f7ae
Ensure follow_new_path is protected by the main worker
mxgrey Nov 26, 2023
2dbe0fc
Make robots stubborn while using the lift
mxgrey Nov 26, 2023
810aa74
Generate task bids asynchronously
mxgrey Nov 26, 2023
5798519
Aggressive end session
mxgrey Nov 26, 2023
5be5939
Introduce mutex deconfliction strategy
mxgrey Nov 26, 2023
6a2a7d4
Skip null events while moving through lift
mxgrey Nov 27, 2023
099cfe2
Add name to Destination API
mxgrey Nov 27, 2023
3b9d37f
Make charger configuration optional
mxgrey Nov 27, 2023
c6f6ae1
Refactor vertex name search
mxgrey Nov 28, 2023
7b24213
Fix parsing of charger config
mxgrey Nov 28, 2023
c28939f
Ignore empty-string dock names
mxgrey Nov 28, 2023
4143e29
Set a schedule horizon when lift sessions begin
mxgrey Nov 28, 2023
65e4535
Publish timestamp from lift supervisor
xiyuoh Nov 29, 2023
fb47ab0
Remove unnecessary debug
mxgrey Nov 29, 2023
4c8874e
Merge remote-tracking branch 'origin/mutex_groups' into mutex_groups
mxgrey Nov 29, 2023
3a0772a
Do not replan after a failed negotiation if the agent is stubborn
mxgrey Dec 5, 2023
ab34a7e
Merge branch 'main' into mutex_groups
mxgrey Dec 12, 2023
3254a56
Fix style and tests
mxgrey Dec 12, 2023
38a91a0
Merge branch 'mutex_groups' of ssh://github.com/open-rmf/rmf_ros2 int…
mxgrey Dec 12, 2023
da88b44
Fix style inside of tests
mxgrey Dec 12, 2023
e4d53e0
Periodically log when a robot is being blocked at a mutex or a lift
mxgrey Dec 13, 2023
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: 7 additions & 0 deletions rmf_charging_schedule/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package rmf_charging_schedule
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.3.2 (XXXX-YY-ZZ)
------------------
* First release
39 changes: 39 additions & 0 deletions rmf_charging_schedule/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
A simple node that takes in a yaml file that describes a schedule for charger
usage in an RMF scenario. The node will watch the clock and publish the
appropriate commands to change the chargers of the robots.

The format for the schedule looks like this:
```
"my_fleet_name":
"00:00": { "robot_1": "charger_A", "robot_2": "charger_B", "robot_3": "queue_A" }
"01:55": { "robot_1": "queue_B" }
"02:00": { "robot_3": "charger_A", "robot_1": "queue_A" }
"03:55": { "robot_2": "queue_B" }
"04:00": { "robot_1": "charger_B", "robot_2": "queue_A" }
```

The time format is `"HH:MM"` where `HH` ranges from `00` to `23` and `MM` ranges
from `00` to `59`. Note that quotes are important because otherwise the yaml
format may confuse the meaning of the colon `:`.

The schedule will cycle every 24 hours.

For each timestamp, only robots that are explicitly mentioned will have their
dedicated charger changed. **It is the responsibility of the schedule file author
to make sure that two robots are never assigned the same charger at the same
time.** Failing to ensure this may cause traffic and task management to misbehave.

When run in simulation mode (`--ros-args --use-sim-time`), the time `00:00` in
the schedule will correspond to `t=0.0` in simulation time.

When run without sim time on, the hours and minutes will correspond to the local
timezone of the machine that the node is run on. To choose a specific timezone
instead of using the system's local timzeone, use the `--timezone` argument and
provide the desired [TZ identifier](https://en.wikipedia.org/wiki/List_of_tz_database_time_zones)
string.

It is advisable that you always put a `00:00` entry that indicates **all** of
the intended charger assignments at midnight. When the node is launched, it will
move through the schedule from the earliest entry up until the last relevant one
and issue an initial charger assignment message based on what the assignments
would have been if the schedule had run from `00:00`.
16 changes: 16 additions & 0 deletions rmf_charging_schedule/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rmf_charging_schedule</name>
<version>2.3.2</version>
<description>Node for a fixed 24-hour rotating charger usage schedule</description>
<maintainer email="mxgrey@intrinsic.ai">Grey</maintainer>
<license>Apache License 2.0</license>

<depend>rclpy</depend>
<depend>rmf_fleet_msgs</depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Empty file.
Empty file.
240 changes: 240 additions & 0 deletions rmf_charging_schedule/rmf_charging_schedule/main.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,240 @@
import sys
import yaml
import datetime
import argparse
from collections import OrderedDict
import bisect
from functools import total_ordering
from zoneinfo import ZoneInfo

from icecream import ic

import rclpy
from rclpy.node import Node, Publisher
from rclpy.qos import (
QoSProfile, QoSHistoryPolicy, QoSReliabilityPolicy, QoSDurabilityPolicy
)

from rmf_fleet_msgs.msg import ChargingAssignment, ChargingAssignments

@total_ordering
class ScheduleTimePoint:
hour: int
minute: int

def __init__(self, hour: int, minute: int):
self.hour = hour
self.minute = minute

def parse(text: str):
segments = text.split(":")
assert len(segments) == 2, (
f'Time point text [{text}] does not have the correct HH:MM format'
)
hh = int(segments[0])
mm = int(segments[1])
assert 0 <= hh and hh < 24, (
f'Time point text [{text}] has an hour value which is outside the '
f'valid range of 0 -> 23.'
)
assert 0 <= mm and mm < 60, (
f'Time point text [{text}] has a minute value which is outside the '
f'valid range of 0 -> 59'
)
return ScheduleTimePoint(hh, mm)

def __eq__(self, other):
return self.hour == other.hour and self.minute == other.minute

def __lt__(self, other):
if self.hour < other.hour:
return True
elif self.hour > other.hour:
return False
return self.minute < other.minute

def __hash__(self):
return hash((self.hour, self.minute))


class Assignment:
fleet: str
robot: str
charger: str

def __init__(self, fleet, robot, charger):
self.fleet = fleet
self.robot = robot
self.charger = charger


def publish_assignments(publisher: Publisher, assignments: dict[dict[str]]):
for fleet, robots in assignments.items():
msg = ChargingAssignments()
msg.fleet_name = fleet
for robot, charger in robots.items():
assignment = ChargingAssignment()
assignment.robot_name = robot
assignment.waypoint_name = charger
# The mode isn't actually used yet, so it doesn't matter what we set
# it to.
assignment.mode = ChargingAssignment.MODE_CHARGE
msg.assignments.append(assignment)

publisher.publish(msg)

def update_assignments(
last_update_index: int | None,
next_update_index: int,
sorted_times: list,
schedule: dict,
assignments: dict,
publisher: Publisher,
node: Node,
):
for key in sorted_times[last_update_index:next_update_index]:
changes: list[Assignment] = schedule[key]
for change in changes:
assignments.setdefault(change.fleet, {})[change.robot] = change.charger
node.get_logger().info(
f'Sending {change.fleet}/{change.robot} to {change.charger} at '
f'{key.hour:02d}:{key.minute:02d}'
)
publish_assignments(publisher, assignments)


def simulation_time(node: Node) -> ScheduleTimePoint:
seconds, _ = node.get_clock().now().seconds_nanoseconds()
minutes: int = int(seconds/60)
hour: int = int((minutes/60) % 24)
minute = minutes % 60
return ScheduleTimePoint(hour, minute)


def real_time(node: Node, timezone: ZoneInfo) -> ScheduleTimePoint:
nanoseconds = float(node.get_clock().now().nanoseconds)
seconds = nanoseconds / 1e9
dt = datetime.datetime.fromtimestamp(seconds, timezone)
return ScheduleTimePoint(dt.hour, dt.minute)


def main(argv=sys.argv):
rclpy.init(args=argv)
node = Node("rmf_charging_schedule")
use_sim_time = node.get_parameter('use_sim_time').value

args_without_ros = rclpy.utilities.remove_ros_args(argv)

parser = argparse.ArgumentParser(
prog='rmf_charging_schedule',
description='Manage a fixed 24-hour charger schedule rotation',
)
parser.add_argument(
'schedule', type=str,
help=(
'A .yaml file representing the schedule. See README for the '
'expected format.'
)
)
parser.add_argument(
'-z', '--timezone', type=str, required=False,
help=(
'Timezone that the 24-hour rotation will be based on. If not '
'provided, the system\'s local timezone will be used.'
)
)
parser.add_argument(
'-t', '--test-time', action='store_true',
help=(
'Use this option to test the real time calculation by printing the '
'current HH:MM based on your settings. This may be used in '
'conjunction with the --timezone option and sim time. The node '
'will immediately quit after printing the time, so this will not '
'publish any assignment messages.'
)
)

args = parser.parse_args(args_without_ros[1:])
schedule_file = args.schedule

if args.timezone is not None:
timezone = ZoneInfo(args.timezone)
else:
timezone = None

if use_sim_time:
get_time = lambda: simulation_time(node)
else:
get_time = lambda: real_time(node, timezone)

if args.test_time:
t = get_time()
print(f'{t.hour:02d}:{t.minute:02d}')
return

with open(schedule_file, 'r') as f:
schedule_yaml = yaml.safe_load(f)

unsorted_schedule = {}
for fleet, change in schedule_yaml.items():
for time_text, assignments in change.items():
time = ScheduleTimePoint.parse(time_text)
entry: list[Assignment] = unsorted_schedule.get(time, list())
for robot, charger in assignments.items():
entry.append(Assignment(fleet, robot, charger))
unsorted_schedule[time] = entry

schedule = {}
sorted_times = []
for time in sorted(unsorted_schedule.keys()):
sorted_times.append(time)
schedule[time] = unsorted_schedule[time]

num_fleets = len(schedule_yaml.keys())
transient_qos = QoSProfile(
history=QoSHistoryPolicy.KEEP_LAST,
depth=2*num_fleets,
reliability=QoSReliabilityPolicy.RELIABLE,
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
)
publisher = node.create_publisher(
ChargingAssignments, 'charging_assignments', transient_qos
)

# fleet -> robot -> charger
assignments = {}
last_update_index = bisect.bisect_right(sorted_times, get_time())
update_assignments(
None, last_update_index,
sorted_times, schedule, assignments, publisher, node,
)

def update():
nonlocal last_update_index
nonlocal sorted_times
nonlocal schedule
nonlocal assignments
nonlocal publisher

next_update_index = bisect.bisect_right(sorted_times, get_time())
if last_update_index < next_update_index:
update_assignments(
last_update_index, next_update_index,
sorted_times, schedule, assignments, publisher, node,
)
last_update_index = next_update_index

elif next_update_index < last_update_index:
# The cycle must have restarted, e.g. passing midnight
update_assignments(
None, next_update_index,
sorted_times, schedule, assignments, publisher, node,
)
last_update_index = next_update_index

node.create_timer(10.0, update)

rclpy.spin(node)

if __name__ == '__main__':
main(sys.argv)
4 changes: 4 additions & 0 deletions rmf_charging_schedule/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/rmf_charging_schedule
[install]
install_scripts=$base/lib/rmf_charging_schedule
25 changes: 25 additions & 0 deletions rmf_charging_schedule/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
from setuptools import setup, find_packages

package_name = 'rmf_charging_schedule'

setup(
name=package_name,
version='2.3.2',
packages=find_packages(),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='Grey',
maintainer_email='mxgrey@intrinsic.ai',
description='A node that manages a fixed schedule for robot charger usage',
license='Apache License 2.0',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'charging_schedule=rmf_charging_schedule.main:main',
],
},
)
20 changes: 20 additions & 0 deletions rmf_fleet_adapter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -255,6 +255,25 @@ target_include_directories(lift_supervisor

# -----------------------------------------------------------------------------

add_executable(mutex_group_supervisor
src/mutex_group_supervisor/main.cpp
)

target_link_libraries(mutex_group_supervisor
PRIVATE
rmf_fleet_adapter
${rclcpp_LIBARRIES}
${rmf_fleet_msgs_LIBRARIES}
)

target_include_directories(mutex_group_supervisor
PRIVATE
${rclcpp_INCLUDE_DIRS}
${rmf_fleet_msgs_INCLUDE_DIRS}
)

# -----------------------------------------------------------------------------

add_executable(experimental_lift_watchdog
src/experimental_lift_watchdog/main.cpp
)
Expand Down Expand Up @@ -502,6 +521,7 @@ install(
mock_traffic_light
full_control
lift_supervisor
mutex_group_supervisor
experimental_lift_watchdog
door_supervisor
robot_state_aggregator
Expand Down
7 changes: 7 additions & 0 deletions rmf_fleet_adapter/include/rmf_fleet_adapter/StandardNames.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,13 @@ const std::string InterruptRequestTopicName = "robot_interrupt_request";
const std::string TaskApiRequests = "task_api_requests";
const std::string TaskApiResponses = "task_api_responses";

const std::string ChargingAssignmentsTopicName = "charging_assignments";

const std::string MutexGroupRequestTopicName = "mutex_group_request";
const std::string MutexGroupStatesTopicName = "mutex_group_states";

const uint64_t Unclaimed = (uint64_t)(-1);

} // namespace rmf_fleet_adapter

#endif // RMF_FLEET_ADAPTER__STANDARDNAMES_HPP
Loading
Loading