Skip to content

Commit dfb656f

Browse files
authored
Fix charging status (#347)
Signed-off-by: Michael X. Grey <[email protected]>
1 parent a01fc2d commit dfb656f

File tree

8 files changed

+65
-11
lines changed

8 files changed

+65
-11
lines changed

rmf_charging_schedule/README.md

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ The format for the schedule looks like this:
1010
"02:00": { "robot_3": "charger_A", "robot_1": "queue_A" }
1111
"03:55": { "robot_2": "queue_B" }
1212
"04:00": { "robot_1": "charger_B", "robot_2": "queue_A" }
13+
parking: ["queue_A", "queue_B"]
1314
```
1415

1516
The time format is `"HH:MM"` where `HH` ranges from `00` to `23` and `MM` ranges
@@ -37,3 +38,7 @@ the intended charger assignments at midnight. When the node is launched, it will
3738
move through the schedule from the earliest entry up until the last relevant one
3839
and issue an initial charger assignment message based on what the assignments
3940
would have been if the schedule had run from `00:00`.
41+
42+
If any of the waypoints are parking points instead of charging points, put them
43+
into a list called `parking`. Note that this node does not support the existence
44+
of a fleet with the name `parking`.

rmf_charging_schedule/rmf_charging_schedule/main.py

Lines changed: 23 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -68,17 +68,23 @@ def __init__(self, fleet, robot, charger):
6868
self.charger = charger
6969

7070

71-
def publish_assignments(publisher: Publisher, assignments: dict[dict[str]]):
71+
def publish_assignments(
72+
publisher: Publisher,
73+
assignments: dict[dict[str]],
74+
parking: list[str]
75+
):
7276
for fleet, robots in assignments.items():
7377
msg = ChargingAssignments()
7478
msg.fleet_name = fleet
7579
for robot, charger in robots.items():
7680
assignment = ChargingAssignment()
7781
assignment.robot_name = robot
7882
assignment.waypoint_name = charger
79-
# The mode isn't actually used yet, so it doesn't matter what we set
80-
# it to.
81-
assignment.mode = ChargingAssignment.MODE_CHARGE
83+
84+
if charger in parking:
85+
assignment.mode = ChargingAssignment.MODE_WAIT
86+
else:
87+
assignment.mode = ChargingAssignment.MODE_CHARGE
8288
msg.assignments.append(assignment)
8389

8490
publisher.publish(msg)
@@ -89,6 +95,7 @@ def update_assignments(
8995
sorted_times: list,
9096
schedule: dict,
9197
assignments: dict,
98+
parking: list[str],
9299
publisher: Publisher,
93100
node: Node,
94101
):
@@ -100,7 +107,7 @@ def update_assignments(
100107
f'Sending {change.fleet}/{change.robot} to {change.charger} at '
101108
f'{key.hour:02d}:{key.minute:02d}'
102109
)
103-
publish_assignments(publisher, assignments)
110+
publish_assignments(publisher, assignments, parking)
104111

105112

106113
def simulation_time(node: Node) -> ScheduleTimePoint:
@@ -176,7 +183,14 @@ def main(argv=sys.argv):
176183
schedule_yaml = yaml.safe_load(f)
177184

178185
unsorted_schedule = {}
186+
parking = []
179187
for fleet, change in schedule_yaml.items():
188+
if fleet == 'parking':
189+
# We treat the parking entry as a special case that simply lists
190+
# which waypoints are parking spots
191+
parking = change
192+
continue
193+
180194
for time_text, assignments in change.items():
181195
time = ScheduleTimePoint.parse(time_text)
182196
entry: list[Assignment] = unsorted_schedule.get(time, list())
@@ -206,7 +220,7 @@ def main(argv=sys.argv):
206220
last_update_index = bisect.bisect_right(sorted_times, get_time())
207221
update_assignments(
208222
None, last_update_index,
209-
sorted_times, schedule, assignments, publisher, node,
223+
sorted_times, schedule, assignments, parking, publisher, node,
210224
)
211225

212226
def update():
@@ -215,20 +229,21 @@ def update():
215229
nonlocal schedule
216230
nonlocal assignments
217231
nonlocal publisher
232+
nonlocal parking
218233

219234
next_update_index = bisect.bisect_right(sorted_times, get_time())
220235
if last_update_index < next_update_index:
221236
update_assignments(
222237
last_update_index, next_update_index,
223-
sorted_times, schedule, assignments, publisher, node,
238+
sorted_times, schedule, assignments, parking, publisher, node,
224239
)
225240
last_update_index = next_update_index
226241

227242
elif next_update_index < last_update_index:
228243
# The cycle must have restarted, e.g. passing midnight
229244
update_assignments(
230245
None, next_update_index,
231-
sorted_times, schedule, assignments, publisher, node,
246+
sorted_times, schedule, assignments, parking, publisher, node,
232247
)
233248
last_update_index = next_update_index
234249

rmf_fleet_adapter/src/rmf_fleet_adapter/TaskManager.cpp

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -812,10 +812,21 @@ std::string TaskManager::robot_status() const
812812
if (_context->override_status().has_value())
813813
return _context->override_status().value();
814814

815+
if (_context->is_charging())
816+
{
817+
if (_context->waiting_for_charger())
818+
{
819+
return "idle";
820+
}
821+
else
822+
{
823+
return "charging";
824+
}
825+
}
826+
815827
if (!_active_task)
816828
return "idle";
817829

818-
// TODO(MXG): Identify if the robot is charging and report that status here
819830
return "working";
820831
}
821832

rmf_fleet_adapter/src/rmf_fleet_adapter/agv/RobotContext.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -846,6 +846,18 @@ bool RobotContext::waiting_for_charger() const
846846
return _waiting_for_charger;
847847
}
848848

849+
//==============================================================================
850+
std::shared_ptr<void> RobotContext::be_charging()
851+
{
852+
return _lock_charging;
853+
}
854+
855+
//==============================================================================
856+
bool RobotContext::is_charging() const
857+
{
858+
return _lock_charging.use_count() > 1;
859+
}
860+
849861
//==============================================================================
850862
const rxcpp::observable<double>& RobotContext::observe_battery_soc() const
851863
{
@@ -1158,6 +1170,7 @@ RobotContext::RobotContext(
11581170
_requester_id(
11591171
_itinerary.description().owner() + "/" + _itinerary.description().name()),
11601172
_charging_wp(state.dedicated_charging_waypoint().value()),
1173+
_lock_charging(std::make_shared<int>(0)),
11611174
_current_task_end_state(state),
11621175
_current_task_id(std::nullopt),
11631176
_task_planner(std::move(task_planner)),

rmf_fleet_adapter/src/rmf_fleet_adapter/agv/RobotContext.hpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -591,6 +591,13 @@ class RobotContext
591591
/// (false)?
592592
bool waiting_for_charger() const;
593593

594+
/// This function will indicate that the robot is currently charging for as
595+
/// long as the return value is held onto.
596+
std::shared_ptr<void> be_charging();
597+
598+
/// Check if the robot is currently doing a battery charging task.
599+
bool is_charging() const;
600+
594601
// Get a reference to the battery soc observer of this robot.
595602
const rxcpp::observable<double>& observe_battery_soc() const;
596603

@@ -847,7 +854,8 @@ class RobotContext
847854
std::size_t _charging_wp;
848855
/// When the robot reaches its _charging_wp, is there to wait for a charger
849856
/// (true) or to actually charge (false)?
850-
bool _waiting_for_charger;
857+
bool _waiting_for_charger = false;
858+
std::shared_ptr<void> _lock_charging;
851859
rxcpp::subjects::subject<double> _battery_soc_publisher;
852860
rxcpp::observable<double> _battery_soc_obs;
853861
rmf_task::State _current_task_end_state;

rmf_fleet_adapter/src/rmf_fleet_adapter/agv/RobotUpdateHandle.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -254,7 +254,7 @@ RobotUpdateHandle& RobotUpdateHandle::set_charger_waypoint(
254254
if (!self)
255255
return;
256256

257-
self->_set_charging(charger_wp, true);
257+
self->_set_charging(charger_wp, false);
258258
RCLCPP_INFO(
259259
self->node()->get_logger(),
260260
"Charger waypoint for robot [%s] set to index [%ld]",

rmf_fleet_adapter/src/rmf_fleet_adapter/phases/WaitForCharge.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -119,6 +119,7 @@ WaitForCharge::Active::Active(
119119
}
120120

121121
_context->current_mode(rmf_fleet_msgs::msg::RobotMode::MODE_CHARGING);
122+
_lock_charging = _context->be_charging();
122123
}
123124

124125
//==============================================================================

rmf_fleet_adapter/src/rmf_fleet_adapter/phases/WaitForCharge.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ class WaitForCharge
7676
rmf_traffic::Time _last_update_time;
7777
double _initial_battery_soc;
7878
double _expected_charging_rate; // % per hour
79+
std::shared_ptr<void> _lock_charging;
7980

8081
};
8182

0 commit comments

Comments
 (0)