Skip to content

Commit

Permalink
REST-API server and client added, timeset capability
Browse files Browse the repository at this point in the history
See relffok#14

Co-authored-by: relffok <57466265+relffok@users.noreply.github.com>
Co-authored-by: soenke.niemann <s.niemann@campus.tu-berlin.de>
Co-authored-by: Niemann <soenke.niemann@ipk.fraunhofer.de>
Co-authored-by: Sönke Niemann <soenke.niemann@wtnet.de>
  • Loading branch information
5 people authored and mintar committed Oct 14, 2022
1 parent e87ba53 commit 3a64ba5
Show file tree
Hide file tree
Showing 14 changed files with 710 additions and 3 deletions.
30 changes: 27 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -297,7 +297,7 @@ to get out of sync quickly (about 1 second per day!). This causes TF transforms
timing out etc. and can be seen using `tf_monitor` (the "Max Delay" is about
3.3 seconds in the following example, but should be less than 0.1 seconds):

#### Using ROS1
#### Determine delay using ROS1

Since MiR is running a roscore (ROS1), the following tf_monitor can be
excecuted after sourcing ROS1 (i.e. noetic) first:
Expand All @@ -320,7 +320,7 @@ Node: unknown_publisher 418.344 Hz, Average Delay: 0.827575 Max Delay: 3.35237
Node: unknown_publisher(static) 465.362 Hz, Average Delay: 0 Max Delay: 0
```

#### Using ROS2
#### Determine delay using ROS2

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:
Expand All @@ -332,10 +332,34 @@ ros2 run tf2_ros tf2_monitor

#### Fix time synchronization manually

* go to "Service" -> "Configuration" -> "System settings" -> "Time settings" -> "Set device time on robot"
* In the Mir dashboard (mir.com in the Mir-Wifi), go to "Service" ->
"Configuration" -> "System settings" -> "Time settings" -> "Set device time
on robot"

Use **load from device** to sync with the system time!

#### **Fix time synchronization using ROS2:**

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.

* Launch the node with the API key and mir hostname's IP address

```bash
ros2 run mir_restapi mir_restapi_server --ros-args -p mir_hostname:='MIR_IP_ADDR' -p mir_restapi_auth:='YOUR_API_KEY'
```

* Call the time sync service from terminal by invoking

```bash
ros2 service call /mir_100_sync_time std_srvs/Trigger
```

#### **After time sync**

Keep in mind, that the time sync causes the mir_bridge to freeze. Therefore online time syncs are not recommended.

### Start `move_base` on the robot

* go to "Service" -> "Configuration" -> "Launch menu", start "Planner"; this starts `move_base` and `amcl` on the robot
Expand Down
29 changes: 29 additions & 0 deletions mir_restapi/LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
BSD 3-Clause License

Copyright (c) 2021, niemsoen
All rights reserved.

Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
5 changes: 5 additions & 0 deletions mir_restapi/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# mir_restapi

ROS server node and client node, that implements calls to the Mir REST API. Currently implemented:

- set MiR's time
Empty file.
259 changes: 259 additions & 0 deletions mir_restapi/mir_restapi/mir_restapi_lib.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,259 @@
import json
import time
import http.client
from datetime import datetime


class HttpConnection:
def __init__(self, logger, address, auth, api_prefix):
self.logger = logger
self.api_prefix = api_prefix
self.http_headers = {"Accept-Language": "en-EN", "Authorization": auth, "Content-Type": "application/json"}
try:
self.connection = http.client.HTTPConnection(host=address, timeout=5)
except Exception as e:
self.logger.warn('Creation of http connection failed')
self.logger.warn(str(e))

def __del__(self):
if self.is_valid():
self.connection.close()

def is_valid(self):
return not self.connection is None

def get(self, path):
if not self.is_valid():
self.connection.connect()
self.connection.request("GET", self.api_prefix + path, headers=self.http_headers)
resp = self.connection.getresponse()
if resp.status < 200 or resp.status >= 300:
self.logger.warn("GET failed with status {} and reason: {}".format(resp.status, resp.reason))
return resp

def post(self, path, body):
self.connection.request("POST", self.api_prefix + path, body=body, headers=self.http_headers)
resp = self.connection.getresponse()
if resp.status < 200 or resp.status >= 300:
self.logger.warn("POST failed with status {} and reason: {}".format(resp.status, resp.reason))
return json.loads(resp.read())

def put(self, path, body):
self.connection.request("PUT", self.api_prefix + path, body=body, headers=self.http_headers)
resp = self.connection.getresponse()
# self.logger.info(resp.read())
if resp.status < 200 or resp.status >= 300:
self.logger.warn("POST failed with status {} and reason: {}".format(resp.status, resp.reason))
return json.loads(resp.read())

def put_no_response(self, path, body):
self.connection.request("PUT", self.api_prefix + path, body=body, headers=self.http_headers)


class MirRestAPI:
def __init__(self, logger, hostname, auth=""):
self.logger = logger
if hostname is not None:
address = hostname + ":80"
# else:
# address="192.168.12.20:80"
self.http = HttpConnection(logger, address, auth, "/api/v2.0.0")

def close(self):
self.http.__del__()
self.logger.info("REST API: Connection closed")

def is_connected(self, print=True):
if not self.http.is_valid():
self.logger.warn('REST API: Http-Connection is not valid')
return False
try:
self.http.connection.connect()
self.http.connection.close()
if print:
self.logger.info("REST API: Connected!")
except Exception as e:
if print:
self.logger.warn('REST API: Attempt to connect failed: ' + str(e))
return False
return True

def is_available(self):
status = json.dumps(self.get_status())
if "service_unavailable" in status:
return False
else:
return True

def wait_for_available(self):
while True:
if self.is_connected(print=False):
if self.is_available():
self.logger.info('REST API: available')
break
else:
self.logger.info('REST API: unavailable... waiting')
time.sleep(1)

def get_status(self):
response = self.http.get("/status")
return json.loads(response.read())

def get_state_id(self):
status = self.get_status()
state_id = status["state_id"]
return state_id

""" Choices are: {3, 4, 11}, State: {Ready, Pause, Manualcontrol}
"""

def set_state_id(self, stateId):
return self.http.put("/status", json.dumps({'state_id': stateId}))

def is_ready(self):
status = self.get_status()
if status["state_id"] != 3: # 3=Ready, 4=Pause, 11=Manualcontrol
self.logger.warn("MIR currently occupied. System state: {}".format(status["state_text"]))
return False
else:
return True

def get_all_settings(self, advanced=False, listGroups=False):
if advanced:
response = self.http.get("/settings/advanced")
elif listGroups:
response = self.http.get("/setting_groups")
else:
response = self.http.get("/settings")
return json.loads(response.read())

def get_group_settings(self, groupID):
response = self.http.get("/setting_groups/" + groupID + "/settings")
return json.loads(response.read())

def set_setting(self, settingID, settingData):
return self.http.put("/setting", json.dumps({settingID: settingData}))

def sync_time(self):
timeobj = datetime.now()
dT = timeobj.strftime("%Y-%m-%dT%X")
response = 'REST API: '
try:
response += str(self.http.put("/status", json.dumps({'datetime': dT})))
except Exception as e:
if str(e) == "timed out":
# setting datetime over REST API seems not to be intended
# that's why there is no response accompanying the PUT request,
# therefore a time out occurs, however time has been set correctly
response += "Set datetime to " + dT
self.logger.warn("REST API: Setting time Mir triggers emergency stop, please unlock.")
self.logger.info(response)

# this is needed, because a timeset restarts the restAPI
self.wait_for_available()

return response
response += " Error setting datetime"
return response

def get_distance_statistics(self):
response = self.http.get("/statistics/distance")
return json.loads(response.read())

def get_positions(self):
response = self.http.get("/positions")
return json.loads(response.read())

def get_pose_guid(self, pos_name):
positions = self.get_positions()
return next((pos["guid"] for pos in positions if pos["name"] == pos_name), None)

def get_missions(self):
response = self.http.get("/missions")
return json.loads(response.read())

def get_mission_guid(self, mission_name):
missions = self.get_missions()
return next((mis["guid"] for mis in missions if mis["name"] == mission_name), None)

def get_sounds(self):
response = self.http.get("/sounds")
return json.loads(response.read())

def move_to(self, position, mission="move_to"):
mis_guid = self.get_mission_guid(mission)
pos_guid = self.get_pose_guid(position)

for (var, txt, name) in zip((mis_guid, pos_guid), ("Mission", "Position"), (mission, position)):
if var is None:
self.logger.warn("No {} named {} available on MIR - Aborting move_to".format(txt, name))
return

body = json.dumps(
{
"mission_id": mis_guid,
"message": "Externally scheduled mission from the MIR Python Client",
"parameters": [{"value": pos_guid, "input_name": "target"}],
}
)

data = self.http.post("/mission_queue", body)
self.logger.info("Mission scheduled for execution under id {}".format(data["id"]))

while data["state"] != "Done":
resp = self.http.get("/mission_queue/{}".format(data["id"]))
data = json.loads(resp.read())
if data["state"] == "Error":
self.logger.warn("Mission failed as robot is in error")
return
self.logger.info(data["state"])
time.sleep(2)

self.logger.info("Mission executed successfully")

def add_mission_to_queue(self, mission_name):
mis_guid = self.get_mission_guid(mission_name)
if mis_guid == None:
self.logger.warn("No Mission named '{}' available on MIR - Aborting move_to".format(mission_name))
return False, -1

# put in mission queue
body = json.dumps(
{"mission_id": str(mis_guid), "message": "Mission scheduled by ROS node mir_restapi_server", "priority": 0}
)

data = self.http.post("/mission_queue", body)
try:
self.logger.info("Mission scheduled for execution under id {}".format(data["id"]))
return True, int(data["id"])
except KeyError:
self.logger.warn("Couldn't schedule mission")
self.logger.warn(str(data))
return False, -1

def is_mission_done(self, mission_queue_id):
try:
# mis_guid = self.get_mission_guid(mission_name)
response = self.http.get("/mission_queue")

except http.client.ResponseNotReady or http.client.CannotSendRequest:
self.logger.info("Http error: Mission with queue_id {} is still in queue".format(mission_queue_id))
self.http.__del__()
return False

# self.logger.info("Mission with queue_id {} is in queue".format(mission_queue_id))
# self.logger.info("Response status {}".format(response.status))
data = json.loads(response.read())

for d in data:
if d["id"] == mission_queue_id:
if d["state"] == 'Done':
self.logger.info("Mission {} is done".format(mission_queue_id))
return True

self.logger.info("Mission with queue_id {} is still in queue".format(mission_queue_id))
return False

def get_system_info(self):
response = self.http.get("/system/info")
return json.loads(response.read())
Loading

0 comments on commit 3a64ba5

Please sign in to comment.