Posted by @dennis-thevara:
I have created a MIR Fleet Adapter based on the template here after I realised that the MIR Adapter in the main repo as well as alexchua0108’s pull request are based on the older implementation of the full_control
adapter. The only changes I’ve made to the fleet_adapter.py
and RobotCommandHandle.py
scripts are modifications to the parameters of the calls to the API client methods.
Within RobotClientAPI.py
I’ve implemented the following methods for RobotAPI
with some changes to their signatures:
check_connection(self) -> Bool
position(self) -> Union[list[float],None]
navigate(self, goal: list[float]) -> Bool
stop(self) -> Bool
navigation_remaining_duration(self) -> int
navigation_completed(self) -> Bool
battery_soc(self) -> Union[float,None]
start_process
and process_completed
are as yet unimplemented.
Functionally it works fine so far, and I am able to send goal positions to our MIR 500 via the terminal using the dispatch_multi_stop
node from rmf_demos_tasks
. That said, we’ve been seeing some strange behavior of the markers in the RViz panel during tracking. I have attached a recording of this below as it’s easier to show than describe.
At this point, I have the following questions:
-
I understand that the velocity of the green marker in the tracking panel is dictated by the
linear
andangular
params of thelimits
trait in the config file used by the adapter code. Is there a way to make this match the actual execution of the path by the robot more precisely instead of trial and error modifications to the velocity params? -
In addition, the execution marker begins moving instantly, instead of when the robot actually begins moving. Is this governed by a setting or param I can tweak to closely match the actual robot?
-
The pink marker that tracks the robot’s actual position frequently teleports to waypoints along its path even before the actual robot has begun moving. Is this possibly an issue with the REST API client or do I need to make any changes to the adapter code to improve the synchronization? For what it’s worth, during testing of the API client separately, I’m able to continuously poll the robot’s status API in a loop with next to no packet drops.
Thanks for your time!
Chosen answer
Answer chosen by @dennis-thevara at 2022-06-01T09:13:05Z.
Answered by @Yadunund:
Hello,
This is likely happening due to your fleet adapter reporting that the navigation has completed before the actual robot begins moving and has to do with how you may have implemented RobotClientAPI.py
and RobotCommandHandle.py
.
Specifically this block which calls the api.navigate()
function should return true only after confirmation that the robot has accepted the request as described here.
Subsequently there is a check here to determine whether the robot has completed navigating to the requested destination.
I can’t say for certain what’s happening with your adapter as I don’t have access to your code but my hunch would be that your implementation of navigation_completed()
is checking whether the task queue in the MiR is empty and if so returning true. But the adapter’s state machine changes to Moving
so fast that the task queue in the MiR fleet manager has not yet been populated with the navigation request you submitted when Idle
. This should be easy to confirm by looking at the printouts in the terminal that is running your adapter. If you see this line printed as soon as you send the task request, then it confirms the above.