Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Perform action #15

Merged
merged 11 commits into from
Nov 21, 2022
17 changes: 17 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,23 @@ In effect, it interfaces the MiR REST API with `open-rmf`, all without needing t

## Usage

### Pre-defined RMF variable move mission

Users are required to define a custom mission with a single `Move` action, which has the variables `x`, `y` and `yaw`, attached to the coordinates `x`, `y` and `yaw` respectively. This is the mission that the fleet adapter will use to send move commands to the robot, while modifying the desired `x`, `y` and `yaw` values.

For more information on how to set up missions, actions and variables, please refer to [official guide documents](https://www.manualslib.com/manual/1941073/Mir-Mir250.html?page=150#manual) (this is for the MiR250).

The name of this custom mission, will need to be passed to the fleet adapter through the configuration file, under `rmf_move_mission`, for each robot's `mir_config`.

```yaml
robots:
ROBOT_NAME:
mir_config:
...
rmf_move_mission: "CUSTOM_MISSION_NAME"
...
```

### Example Entry Point

An example usage of the implemented adapter can be found in the `fleet_adapter_mir/fleet_adapter_mir.py` file. It takes in a configuration file and navigation graph, sets everything up, and spins up the fleet adapter.
Expand Down
14 changes: 10 additions & 4 deletions configs/mir_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,18 @@ robots:
# So for now, this name is the name used in the script only.
my_test_robot:
mir_config:
base_url: "http://some_url"
user: "some_user"
password: "some_password"
base_url: "http://some.ip.address/api/v2.0.0/"
user: "application/json"
password: "Basic HASH_OF_PASSWORD_OBTAINED_AT_API_DOCUMENTATION_PAGE"
rmf_move_mission: "rmf_default_move_mission" # This mission must be predefined
dock_and_charge_mission: "dock_to_charger" # This mission must be predefined

rmf_config:
robot_state_update_frequency: 1
start:
map_name: "L1"

max_merge_waypoint_distance: 3.0
max_merge_lane_distance: 3.0
# NOTE(CH3):
# If you leave these empty, the robot will try to figure it out on init
# from the MiR reported location.
Expand All @@ -28,6 +31,8 @@ robots:
# ON the waypoint!
waypoint_index: 0 # Optional
orientation: 0.0 # Optional, radians
charger:
waypoint: "charger_waypoint"


# NODE CONFIG ==================================================================
Expand Down Expand Up @@ -93,3 +98,4 @@ rmf_fleet:
delivery: False
clean: False
finishing_request: "nothing" # [park, charge, nothing]
action_categories: ["custom_mission_1"]
29 changes: 23 additions & 6 deletions fleet_adapter_mir/MiRClientAPI.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ def __init__(self, prefix, headers, timeout=10.0, debug=False):
print(f"HTTP error: {http_err}")
except Exception as err:
print(f"Other error: {err}")

def status_get(self):
if not self.connected:
return
Expand All @@ -49,7 +49,7 @@ def missions_get(self):
print(f"HTTP error: {http_err}")
except Exception as err:
print(f"Other error: {err}")

def positions_get(self):
if not self.connected:
return
Expand All @@ -63,10 +63,27 @@ def positions_get(self):
except Exception as err:
print(f"Other error: {err}")

def mission_queue_post(self, mission_id):
def mission_queue_id_get(self, mission_queue_id):
if not self.connected:
return
data = {"mission_id": mission_id}
try:
response = requests.get(self.prefix + f'mission_queue/{mission_queue_id}', headers = self.headers, timeout=self.timeout)
return response.json()
except HTTPError as http_err:
print(f"HTTP error: {http_err}")
except Exception as err:
print(f"Other here error: {err}")

def mission_queue_post(self, mission_id, full_mission_description=None):
if not self.connected:
return
data = {'mission_id': mission_id}
if full_mission_description is not None:
data = full_mission_description
if mission_id != full_mission_description['mission_id']:
print(f'Inconsistent mission id, provided [{mission_id}], full_mission_description: [{full_mission_description}]')
return

try:
response = requests.post(self.prefix + 'mission_queue' , headers = self.headers, data=json.dumps(data), timeout = self.timeout)
if self.debug:
Expand All @@ -81,7 +98,7 @@ def missions_mission_id_actions_post(self,mission_id,body):
if not self.connected:
return
try:
response = requests.post(self.prefix + 'missions/' +mission_id +'/actions' , headers = self.headers, data=json.dumps(body), timeout = self.timeout)
response = requests.post(self.prefix + 'missions/' + mission_id +'/actions' , headers = self.headers, data=json.dumps(body), timeout = self.timeout)
if self.debug:
print(f"Response: {response.json()}")
print(response.status_code)
Expand Down Expand Up @@ -130,7 +147,7 @@ def status_put(self, state_id):
print(f"HTTP error: {http_err}")
except Exception as err:
print(f"Other error: {err}")

def mission_queue_delete(self):
if not self.connected:
return
Expand Down
Loading