Skip to content

Commit b96e3e4

Browse files
niemsoenrelffoksoenke.niemannNiemannSönke Niemann
authored
REST-API server and client added, timeset capability (#14)
* initial commit: added restapi state of work * added mir_ready publisher * added reliable QOS for mir_bridge_ready topic * added mir_bridge_ready=false on crash/shutdown * attribute bugfix * added readiness polling and simplified ready publishing * uneccesary main->publish_mir_ready_state: button checks bridge alive * uneccesary main->publish_mir_ready_state: button checks bridge alive * changed mir_ready pub/sub to Trigger-service * possible bugfix * changed response to success=True always and message=True/False * Revert "changed response to success=True always and message=True/False" This reverts commit f31efb8. * added custom CheckReady srv-definition * find bug in service * renamed interface to match usb_pushbutton * fixed dependency * fixed another dependency * Revert "Merge pull request #2 from niemsoen/mir-bridge-as-service-server" This reverts commit cf0f5c1, reversing changes made to 39e025e. * Use std_srvs/Trigger as mir-ready-service Type * changed structure to service-client communication * fix for build error? * wrong directory name * added logging output * bugfix * better logging * added message to response of service call * bugfix * added auth as parameter * catch token not set * bugfix response * added check for error in setting as response to service call * better log * introduced parameters for hostname and auth-token * make sure api handle is setup at launch * better function names * file rename * launch of mir driver triggers launch of restapi_server * mir_bridge creates restapi_client node * import error in mir_bridge for MirRestAPIClient * include test client for rest api * add sleep for test call * working, launch file not needed * add client in mir_bridge.py * trying to fix import * Revert "trying to fix import" This reverts commit 1a97c70. * fix for import bug * fix message type error * try to fix connection refusal of rosbridge after restapi * try to replace sleep after setTime waiting for reboot * catch CannotSendRequest * replace print with logger * disable status call * try output of get status call * wait for restapi restart working * make waiting for availability more elegant * clean-up * removed unused imports * add potential fix * Call mir_restapi_server in tendobot_driver * Added api-call abstarction layer & tested api call while bridge connected (#5) * init (#6) Co-authored-by: Sönke Niemann <[email protected]> * readme section: time sync in ros2 /w restapi * remove automatic time sync call at driver start * improved naming style in mir_restapi * catch case of no api token set, warn user * added more untested calls * added waiting condition for honking * failed try to find system time in restapi * added client for time sync * wait for service available * added requested changes Co-authored-by: relffok <[email protected]> Co-authored-by: soenke.niemann <[email protected]> Co-authored-by: Niemann <[email protected]> Co-authored-by: Sönke Niemann <[email protected]>
1 parent 29e1a47 commit b96e3e4

File tree

14 files changed

+740
-3
lines changed

14 files changed

+740
-3
lines changed

README.md

Lines changed: 17 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -277,7 +277,7 @@ to get out of sync quickly (about 1 second per day!). This causes TF transforms
277277
timing out etc. and can be seen using `tf_monitor` (the "Max Delay" is about
278278
3.3 seconds in the following example, but should be less than 0.1 seconds):
279279

280-
#### **Using ROS1** (optional)
280+
#### **Determine delay using ROS1** (optional)
281281

282282
Since MiR is running a roscore (ROS1), the following tf_monitor can be excecuted after sourcing ROS1 (i.e. noetic) first:
283283

@@ -300,7 +300,7 @@ Node: unknown_publisher 418.344 Hz, Average Delay: 0.827575 Max Delay: 3.35237
300300
Node: unknown_publisher(static) 465.362 Hz, Average Delay: 0 Max Delay: 0
301301
```
302302

303-
#### **Using ROS2**
303+
#### **Determine delay using ROS2**
304304

305305
If you don't have a ROS1 distro installed, you'll need to run the `mir_driver` first and execute the following once a connection is established:
306306

@@ -311,9 +311,23 @@ ros2 run tf2_ros tf2_monitor
311311

312312
#### **Fix time synchronization manually:**
313313

314-
* go to "Service" -> "Configuration" -> "System settings" -> "Time settings" -> "Set device time on robot"
314+
* In the Mir dashboard (mir.com in the Mir-Wifi), go to "Service" -> "Configuration" -> "System settings" -> "Time settings" -> "Set device time on robot"
315315
Use **load from device** to sync with the system time!
316316

317+
#### **Fix time synchronization using ROS2:**
318+
319+
From the package `mir_restapi` a node called `mir_restapi_server` can be run, which can execute a time sync REST API call from the driver's host machine to the Mir's host.
320+
* Launch the node with the API key and mir hostname's IP address
321+
322+
ros2 run mir_restapi mir_restapi_server --ros-args -p mir_hostname:='MIR_IP_ADDR' -p mir_restapi_auth:='YOUR_API_KEY'
323+
* Call the time sync service from terminal by invoking
324+
325+
ros2 service call /mir_100_sync_time std_srvs/Trigger
326+
327+
#### **After time sync**
328+
329+
Keep in mind, that the time sync causes the mir_bridge to freeze. Therefore online time syncs are not recommended.
330+
317331

318332
### Start `move_base` on the robot
319333

mir_restapi/LICENSE

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
BSD 3-Clause License
2+
3+
Copyright (c) 2021, niemsoen
4+
All rights reserved.
5+
6+
Redistribution and use in source and binary forms, with or without
7+
modification, are permitted provided that the following conditions are met:
8+
9+
1. Redistributions of source code must retain the above copyright notice, this
10+
list of conditions and the following disclaimer.
11+
12+
2. Redistributions in binary form must reproduce the above copyright notice,
13+
this list of conditions and the following disclaimer in the documentation
14+
and/or other materials provided with the distribution.
15+
16+
3. Neither the name of the copyright holder nor the names of its
17+
contributors may be used to endorse or promote products derived from
18+
this software without specific prior written permission.
19+
20+
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21+
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22+
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23+
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24+
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25+
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26+
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27+
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28+
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29+
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

mir_restapi/README.md

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
# mir_restapi
2+
ROS server node and client node, that implements calls to the Mir REST API. Currently implemented:
3+
- set MiR's time
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
Lines changed: 266 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,266 @@
1+
import json
2+
import time
3+
import http.client
4+
from datetime import datetime
5+
6+
class HttpConnection():
7+
8+
def __init__(self, logger, address, auth, api_prefix):
9+
self.logger = logger
10+
self.api_prefix = api_prefix
11+
self.http_headers = {
12+
"Accept-Language":"en-EN",
13+
"Authorization":auth,
14+
"Content-Type":"application/json"}
15+
try:
16+
self.connection = http.client.HTTPConnection(host=address, timeout=5)
17+
except Exception as e:
18+
self.logger.warn('Creation of http connection failed')
19+
self.logger.warn(str(e))
20+
21+
def __del__(self):
22+
if self.is_valid():
23+
self.connection.close()
24+
25+
def is_valid(self):
26+
return not self.connection is None
27+
28+
def get(self, path):
29+
if not self.is_valid():
30+
self.connection.connect()
31+
self.connection.request("GET", self.api_prefix+path, headers = self.http_headers)
32+
resp = self.connection.getresponse()
33+
if resp.status <200 or resp.status>=300:
34+
self.logger.warn("GET failed with status {} and reason: {}".format(resp.status, resp.reason))
35+
return resp
36+
37+
def post(self, path, body):
38+
self.connection.request("POST", self.api_prefix+path,body=body, headers=self.http_headers)
39+
resp = self.connection.getresponse()
40+
if resp.status <200 or resp.status>=300:
41+
self.logger.warn("POST failed with status {} and reason: {}".format(resp.status, resp.reason))
42+
return json.loads(resp.read())
43+
44+
def put(self, path, body):
45+
self.connection.request("PUT", self.api_prefix+path,body=body, headers=self.http_headers)
46+
resp = self.connection.getresponse()
47+
#self.logger.info(resp.read())
48+
if resp.status <200 or resp.status>=300:
49+
self.logger.warn("POST failed with status {} and reason: {}".format(resp.status, resp.reason))
50+
return json.loads(resp.read())
51+
52+
def put_no_response(self, path, body):
53+
self.connection.request("PUT", self.api_prefix+path,body=body, headers=self.http_headers)
54+
55+
class MirRestAPI():
56+
57+
def __init__(self, logger, hostname, auth = ""):
58+
self.logger = logger
59+
if hostname is not None:
60+
address = hostname + ":80"
61+
# else:
62+
# address="192.168.12.20:80"
63+
self.http = HttpConnection(logger, address, auth, "/api/v2.0.0")
64+
65+
def close(self):
66+
self.http.__del__()
67+
self.logger.info("REST API: Connection closed")
68+
69+
def is_connected(self, print=True):
70+
if not self.http.is_valid():
71+
self.logger.warn('REST API: Http-Connection is not valid')
72+
return False
73+
try:
74+
self.http.connection.connect()
75+
self.http.connection.close()
76+
if print:
77+
self.logger.info("REST API: Connected!")
78+
except Exception as e:
79+
if print:
80+
self.logger.warn('REST API: Attempt to connect failed: ' + str(e))
81+
return False
82+
return True
83+
84+
def is_available(self):
85+
status = json.dumps(self.get_status())
86+
if "service_unavailable" in status:
87+
return False
88+
else:
89+
return True
90+
91+
def wait_for_available(self):
92+
while True:
93+
if self.is_connected(print=False):
94+
if self.is_available():
95+
self.logger.info('REST API: available')
96+
break
97+
else:
98+
self.logger.info('REST API: unavailable... waiting')
99+
time.sleep(1)
100+
101+
def get_status(self):
102+
response = self.http.get("/status")
103+
return json.loads(response.read())
104+
105+
def get_state_id(self):
106+
status = self.get_status()
107+
state_id = status["state_id"]
108+
return state_id
109+
110+
""" Choices are: {3, 4, 11}, State: {Ready, Pause, Manualcontrol}
111+
"""
112+
def set_state_id(self, stateId):
113+
return self.http.put("/status", json.dumps({'state_id': stateId}))
114+
115+
def is_ready(self):
116+
status = self.get_status()
117+
if status["state_id"] != 3: # 3=Ready, 4=Pause, 11=Manualcontrol
118+
self.logger.warn("MIR currently occupied. System state: {}".format(status["state_text"]))
119+
return False
120+
else:
121+
return True
122+
123+
def get_all_settings(self, advanced=False, listGroups=False):
124+
if advanced:
125+
response = self.http.get("/settings/advanced")
126+
elif listGroups:
127+
response = self.http.get("/setting_groups")
128+
else:
129+
response = self.http.get("/settings")
130+
return json.loads(response.read())
131+
132+
def get_group_settings(self, groupID):
133+
response = self.http.get("/setting_groups/" + groupID + "/settings")
134+
return json.loads(response.read())
135+
136+
def set_setting(self, settingID, settingData):
137+
return self.http.put("/setting", json.dumps({settingID: settingData}))
138+
139+
def sync_time(self):
140+
timeobj = datetime.now()
141+
dT = timeobj.strftime("%Y-%m-%dT%X")
142+
response = 'REST API: '
143+
try:
144+
response += str(self.http.put("/status", json.dumps({'datetime': dT})))
145+
except Exception as e:
146+
if str(e) == "timed out":
147+
# setting datetime over REST API seems not to be intended
148+
# that's why there is no response accompanying the PUT request,
149+
# therefore a time out occurs, however time has been set correctly
150+
response += "Set datetime to " + dT
151+
self.logger.warn("REST API: Setting time Mir triggers emergency stop, please unlock.")
152+
self.logger.info(response)
153+
154+
# this is needed, because a timeset restarts the restAPI
155+
self.wait_for_available()
156+
157+
return response
158+
response += " Error setting datetime"
159+
return response
160+
161+
def get_distance_statistics(self):
162+
response = self.http.get("/statistics/distance")
163+
return json.loads(response.read())
164+
165+
def get_positions(self):
166+
response = self.http.get("/positions")
167+
return json.loads(response.read())
168+
169+
def get_pose_guid(self, pos_name):
170+
positions = self.get_positions()
171+
return next((pos["guid"] for pos in positions if pos["name"]==pos_name), None)
172+
173+
def get_missions(self):
174+
response = self.http.get("/missions")
175+
return json.loads(response.read())
176+
177+
def get_mission_guid(self, mission_name):
178+
missions = self.get_missions()
179+
return next((mis["guid"] for mis in missions if mis["name"]==mission_name), None)
180+
181+
def get_sounds(self):
182+
response = self.http.get("/sounds")
183+
return json.loads(response.read())
184+
185+
def move_to(self, position, mission="move_to"):
186+
mis_guid = self.get_mission_guid(mission)
187+
pos_guid = self.get_pose_guid(position)
188+
189+
for (var, txt, name) in zip((mis_guid, pos_guid),("Mission", "Position"),(mission, position)):
190+
if var is None:
191+
self.logger.warn("No {} named {} available on MIR - Aborting move_to".format(txt,name))
192+
return
193+
194+
body = json.dumps({
195+
"mission_id": mis_guid,
196+
"message": "Externally scheduled mission from the MIR Python Client",
197+
"parameters": [{
198+
"value": pos_guid,
199+
"input_name": "target"
200+
}]})
201+
202+
data = self.http.post("/mission_queue", body)
203+
self.logger.info("Mission scheduled for execution under id {}".format(data["id"]))
204+
205+
while data["state"] != "Done":
206+
resp = self.http.get("/mission_queue/{}".format(data["id"]))
207+
data = json.loads(resp.read())
208+
if data["state"] == "Error":
209+
self.logger.warn("Mission failed as robot is in error")
210+
return
211+
self.logger.info(data["state"])
212+
time.sleep(2)
213+
214+
self.logger.info("Mission executed successfully")
215+
216+
def add_mission_to_queue(self, mission_name):
217+
mis_guid = self.get_mission_guid(mission_name)
218+
if mis_guid == None:
219+
self.logger.warn("No Mission named '{}' available on MIR - Aborting move_to".format(mission_name))
220+
return False, -1
221+
222+
# put in mission queue
223+
body = json.dumps(
224+
{
225+
"mission_id": str(mis_guid),
226+
"message": "Mission scheduled by ROS node mir_restapi_server",
227+
"priority": 0
228+
}
229+
)
230+
231+
data = self.http.post("/mission_queue", body)
232+
try:
233+
self.logger.info("Mission scheduled for execution under id {}".format(data["id"]))
234+
return True, int(data["id"])
235+
except KeyError:
236+
self.logger.warn("Couldn't schedule mission")
237+
self.logger.warn(str(data))
238+
return False, -1
239+
240+
def is_mission_done(self, mission_queue_id):
241+
try:
242+
# mis_guid = self.get_mission_guid(mission_name)
243+
response = self.http.get("/mission_queue")
244+
245+
except http.client.ResponseNotReady or http.client.CannotSendRequest:
246+
self.logger.info("Http error: Mission with queue_id {} is still in queue".format(mission_queue_id))
247+
self.http.__del__()
248+
return False
249+
250+
# self.logger.info("Mission with queue_id {} is in queue".format(mission_queue_id))
251+
# self.logger.info("Response status {}".format(response.status))
252+
data = json.loads(response.read())
253+
254+
for d in data:
255+
if d["id"]==mission_queue_id:
256+
if d["state"] == 'Done':
257+
self.logger.info("Mission {} is done".format(mission_queue_id))
258+
return True
259+
260+
self.logger.info("Mission with queue_id {} is still in queue".format(mission_queue_id))
261+
return False
262+
263+
def get_system_info(self):
264+
response = self.http.get("/system/info")
265+
return json.loads(response.read())
266+

0 commit comments

Comments
 (0)