Skip to content

Commit

Permalink
MiR Connector: Allow connector to start disconnected and publish `api…
Browse files Browse the repository at this point in the history
…_connected` value (#36)
  • Loading branch information
b-Tomas authored Feb 5, 2025
1 parent a2598a7 commit 01db750
Show file tree
Hide file tree
Showing 4 changed files with 48 additions and 6 deletions.
42 changes: 39 additions & 3 deletions mir_connector/inorbit_mir_connector/src/connector.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,10 @@
import pytz
import math
import uuid
from threading import Thread
import logging
import requests
from tenacity import retry, wait_exponential_jitter, before_sleep_log, retry_if_exception_type
from threading import Thread, Lock
from inorbit_connector.connector import Connector
from inorbit_edge.robot import COMMAND_CUSTOM_COMMAND
from inorbit_edge.robot import COMMAND_MESSAGE
Expand Down Expand Up @@ -54,6 +57,10 @@ def __init__(self, robot_id: str, config: MiR100Config) -> None:
create_user_scripts_dir=True,
)
self.config = config
# Missions group id for temporary missions
# If None, it indicates the missions group has not been set up
self.tmp_missions_group_id = None
self.tmp_missions_group_id_lock = Lock()

# Configure the connection to the robot
self.mir_api = MirApiV2(
Expand Down Expand Up @@ -94,7 +101,7 @@ def __init__(self, robot_id: str, config: MiR100Config) -> None:
)

# Get or create the required missions and mission groups
self.setup_connector_missions()
Thread(target=self.setup_connector_missions, daemon=True).start()

def _inorbit_command_handler(self, command_name, args, options):
"""Callback method for command messages.
Expand Down Expand Up @@ -218,8 +225,8 @@ def _connect(self) -> None:

def _disconnect(self):
"""Disconnect from any external services"""
self.cleanup_connector_missions()
super()._disconnect()
self.cleanup_connector_missions()
if self.ws_enabled:
self.mir_ws.disconnect()

Expand All @@ -235,6 +242,7 @@ def _execution_loop(self):
self.metrics = self.mir_api.get_metrics()
except Exception as ex:
self._logger.error(f"Failed to get robot API data: {ex}")
self.publish_api_error()
return
# publish pose
pose_data = {
Expand Down Expand Up @@ -277,6 +285,9 @@ def _execution_loop(self):
"mode_text": mode_text,
"robot_model": self.status["robot_model"],
"waiting_for": self.mission_tracking.waiting_for_text,
# See self.publish_api_error()
# This clears the error without publishing a separate message
"api_connected": True,
}
self._logger.debug(f"Publishing key values: {key_values}")
self._robot_session.publish_key_values(key_values)
Expand All @@ -300,12 +311,20 @@ def _execution_loop(self):
except Exception:
self._logger.exception("Error reporting mission")

def publish_api_error(self):
"""Publish an error message when the API call fails.
This value can be used for setting up status and incidents in InOrbit"""
self._robot_session.publish_key_values({"api_connected": False})

def send_waypoint_over_missions(self, pose):
"""Use the connector's mission group to create a move mission to a designated pose."""
mission_id = str(uuid.uuid4())
connector_type = self.config.connector_type
firmware_version = self.config.connector_config.mir_firmware_version

if not self.tmp_missions_group_id:
raise Exception("Connector missions group not set up")

self.mir_api.create_mission(
group_id=self.tmp_missions_group_id,
name="Move to waypoint",
Expand Down Expand Up @@ -345,9 +364,19 @@ def send_waypoint_over_missions(self, pose):
)
self.mir_api.queue_mission(mission_id)

@retry(
wait=wait_exponential_jitter(max=10),
before_sleep=before_sleep_log(logging.getLogger(__name__), logging.WARNING),
retry=retry_if_exception_type(requests.exceptions.ConnectionError),
)
def setup_connector_missions(self):
"""Find and store the required missions and mission groups, or create them if they don't
exist."""
with self.tmp_missions_group_id_lock:
# If the missions group is not None it means it was already setup or it was deleted
# intentionally and should not be set up again
if self.tmp_missions_group_id is not None:
return
self._logger.info("Setting up connector missions")
# Find or create the missions group
mission_groups: list[dict] = self.mir_api.get_mission_groups()
Expand All @@ -373,6 +402,13 @@ def setup_connector_missions(self):

def cleanup_connector_missions(self):
"""Delete the missions group created at startup"""
with self.tmp_missions_group_id_lock:
# If the missions group id is None, it means it was not set up and there is nothing to
# clean up. Change its value to indicate it should not be set up, in case there is a
# running setup thread.
if self.tmp_missions_group_id is None:
self.tmp_missions_group_id = ""
return
self._logger.info("Cleaning up connector missions")
self._logger.info(f"Deleting missions group {self.tmp_missions_group_id}")
self.mir_api.delete_mission_group(self.tmp_missions_group_id)
Expand Down
7 changes: 5 additions & 2 deletions mir_connector/inorbit_mir_connector/src/mir_api/mir_api_v2.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,10 @@ def __init__(
self.mir_username = mir_username
self.mir_password = mir_password
self.api_session = self._create_api_session()
self.web_session = self._create_web_session()

def _get_web_session(self) -> requests.Session:
if not self.web_session:
self.web_session = self._create_web_session()

def _create_api_session(self) -> requests.Session:
session = requests.Session()
Expand Down Expand Up @@ -270,7 +273,7 @@ def send_waypoint(self, pose):
"orientation": orientation_degs,
"mode": "map-go-to-coordinates",
}
response = self._get(self.mir_base_url, self.web_session, params=parameters)
response = self._get(self.mir_base_url, self._get_web_session(), params=parameters)
self.logger.info(response.text)

def get_status(self):
Expand Down
4 changes: 3 additions & 1 deletion mir_connector/inorbit_mir_connector/tests/test_connector.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ def connector(monkeypatch, tmp_path):
),
)
connector.mir_api = MagicMock()
connector.mir_api.get_last_api_call_successful.return_value = True
connector._robot_session = MagicMock()
return connector

Expand Down Expand Up @@ -380,15 +381,16 @@ def run_loop_once():
"mode_text": "Mission",
"robot_model": "MiR100",
"waiting_for": "",
"api_connected": True,
}
)

connector.mir_api.get_metrics.side_effect = Exception("Test")
connector._robot_session.reset_mock()
run_loop_once()
assert not connector._robot_session.publish_pose.called
assert not connector._robot_session.publish_key_values.called
assert not connector._robot_session.publish_odometry.called
connector._robot_session.publish_key_values.assert_called_with({"api_connected": False})


def test_missions_garbage_collector(connector):
Expand Down
1 change: 1 addition & 0 deletions mir_connector/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
"psutil==5.9",
"websocket-client==1.7.0",
"uuid==1.30",
"tenacity==9.0.0",
]

test_requirements = [
Expand Down

0 comments on commit 01db750

Please sign in to comment.