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

Reflect standard 1.0 #7

Open
wants to merge 9 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
155 changes: 94 additions & 61 deletions AMR_Interop_Standard.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"definitions": {
"quaternion": {
"description": "Quaternion representation of an angle",
"description": "Quaternion representation of an pose",
"type": "object",
"required": ["x", "y", "z", "w"],
"properties": {
Expand All @@ -11,19 +11,52 @@
"w": { "type": "number" }
}
},
"datumReferencePoint": {
"description": "A Datum Reference Point",
"type": "object",
"required": ["id", "name", "x", "y"],
"properties": {
"id": {
"type": "string",
"format": "uuid"
},
"name": { "type": "string" },
"x": { "type": "number" },
"y": { "type": "number" }
}
},
"planarDatum": {
"description": "Planar Datum",
"type": "object",
"required": ["id", "name", "level", "datumReferencePoints"],
"properties": {
"id": { "type": "string" },
"name": { "type": "string" },
"level": { "type": "integer" },
"datumReferencePoints": {
"description": "Datum Reference Point ids",
"type": "array",
"items": {
"type": "string",
"format": "uuid"
},
"minItems": 2
}
}
},
"location": {
"description": "Location of an object or AMR",
"type": "object",
"required": ["x", "y", "angle", "planarDatum"],
"required": ["x", "y", "pose", "planarDatum"],
"properties": {
"x": { "type": "number" },
"y": { "type": "number" },
"z": {
"type": "number",
"z": {
"type": "number",
"default" : 0
},
"angle" : { "$ref": "#/definitions/quaternion" },
"planarDatum": {
"pose" : { "$ref": "#/definitions/quaternion" },
"planarDatum": {
"description": "Id of planarDatum AMR is referencing",
"type": "string",
"format": "uuid"
Expand All @@ -33,21 +66,21 @@
"predictedLocation": {
"description": "Predicted future location of an object or AMR",
"type": "object",
"required": ["timestamp", "x", "y", "angle"],
"required": ["timestamp", "x", "y", "pose"],
"properties": {
"timestamp": {
"timestamp": {
"description": "Predicted UTC time AMR will reach this location",
"type": "string",
"format": "date-time"
"type": "string",
"format": "date-time"
},
"x": { "type": "number" },
"y": { "type": "number" },
"z": {
"type": "number",
"z": {
"type": "number",
"default" : 0
},
"angle" : { "$ref": "#/definitions/quaternion" },
"planarDatumUUID": {
"pose" : { "$ref": "#/definitions/quaternion" },
"planarDatumUUID": {
"description": "Only necessary if different from AMRs current planarDatum",
"type": "string",
"format": "uuid"
Expand All @@ -68,74 +101,74 @@
"timestamp": { "type": "string", "format": "date-time" },
"manufacturerName": { "type": "string" },
"robotModel": { "type": "string" },
"robotSerialNumber": {
"robotSerialNumber": {
"description": "Unique robot identifier that ideally can be physically linked to the AMR",
"type": "string" },
"baseRobotEnvelope": {
"baseRobotEnvelope": {
"description": "Footprint of robot based on orientation - centered on current location.",
"type": "object",
"required": ["x", "y"],
"properties": {
"x": { "type": "number" },
"y": { "type": "number" },
"z": {
"type": "number",
"z": {
"type": "number",
"default" : 0
}
}
},
"maxSpeed": {
"maxSpeed": {
"description": "Max robot speed in m/s",
"type": "number"
"type": "number"
},
"maxRunTime": {
"maxRunTime": {
"description": "Estimated Runtime in hours",
"type": "number"
},
"emergencyContactInformation": {
"emergencyContactInformation": {
"description": "Emergency Contact - preferrably phone number",
"type": "string"
},
"chargerType": {
"chargerType": {
"description": "Type of charger",
"type": "string"
},
"supportVendorName": {
"supportVendorName": {
"description": "Vendor that supplied robot",
"type": "string"
},
"supportVendorContactInformation": {
"supportVendorContactInformation": {
"description": "Contect information for vendor",
"type": "string"
},
"productDocumentation": {
"productDocumentation": {
"description": "Link to product documenation",
"type": "string",
"format": "uri"
},
"thumbnailImage": {
"thumbnailImage": {
"description": "Link to thumbnail graphic stored as PNG",
"type": "string",
"format": "uri"
},
"cargoType": {
},
"cargoType": {
"description": "Discription of cargo",
"type": "string"
},
"cargoMaxVolume": {
},
"cargoMaxVolume": {
"description": "Max volume of cargo in meters",
"type": "object",
"required": ["x", "y"],
"properties": {
"x": { "type": "number" },
"y": { "type": "number" },
"z": {
"type": "number",
"z": {
"type": "number",
"default" : 0
}
}
},
"cargoMaxWeight": {
"cargoMaxWeight": {
"description": "Max weight of cargo in kg",
"type": "string"
}
Expand All @@ -152,30 +185,47 @@
"format": "uuid"
},
"timestamp": { "type": "string", "format": "date-time" },
"operationalState": {
"operationalState": {
"description": "Current action the robot is performing",
"type": "string",
"enum": ["navigating", "idle", "disabled", "offline", "charging", "waitingHumanEvent", "waitingExternalEvent", "waitingInternalEvent", "manualOverride"]
"enum": ["navigating", "idle", "disabled", "offline", "charging", "waitingHumanEvent", "waitingExternalEvent", "waitingInternalEvent", "manualMode"]
},
"location": {
"location": {
"description": "Current Location of AMR",
"$ref": "#/definitions/location"
"$ref": "#/definitions/location"
},
"velocity": {
"errorCodes" : {
"description": "List of current error states - should be omitted for normal operation",
"type": "array",
"items": {
"type": "string"
},
"uniqueItems": true
},
"velocity": {
"description": "Current velocity of AMR",
"type": "object",
"required": ["linear"],
"properties": {
"linear": {
"linear": {
"description": "Linear velocity in m/s in heading direction, forward is postive",
"type": "number"
"type": "number"
},
"angular" : {
"angular" : {
"description": "Angular velocity in quaternions per second",
"$ref": "#/definitions/quaternion"
"$ref": "#/definitions/quaternion"
}
}
},
"nextWorkingLocations" : {
"description": "Next working location(s). It is recommended that at least the destination is provided",
"type": "array",
"items": {
"$ref": "#/definitions/predictedLocation"
},
"maxItems": 10,
"uniqueItems": true
},
"batteryPercentage" : {
"description": "Percentage of battery remaining",
"type": "number",
Expand All @@ -193,27 +243,10 @@
"minimum": 0,
"inclusiveMaximum": 100
},
"errorCodes" : {
"description": "List of current error states - should be omitted for normal operation",
"type": "array",
"items": {
"type": "string"
},
"uniqueItems": true
},
"destinations" : {
"description": "Target destination(s) of AGV",
"type": "array",
"items": {
"$ref": "#/definitions/predictedLocation"
},
"maxItems": 10,
"uniqueItems": true
},
"path" : {
"description": "Short term path of AGV ~10 sec",
"type": "array",
"items": {
"items": {
"$ref": "#/definitions/predictedLocation"
},
"maxItems": 10,
Expand Down
20 changes: 10 additions & 10 deletions MassRobotics-AMR-Sender/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
from datetime import datetime, timezone, timedelta

OPERATIONAL_STATES = ["navigating", "idle", "disabled", "offline", "charging",
"waitingHumanEvent", "waitingExternalEvent", "waitingInternalEvent", "manualOverride"]
"waitingHumanEvent", "waitingExternalEvent", "waitingInternalEvent", "manualMode"]

async def sendMessage(uri):
async with websockets.connect(uri) as websocket:
Expand Down Expand Up @@ -57,24 +57,24 @@ async def sendMessage(uri):

# Generate a random location, simulating that the AMR moves in circles
r = 20
angle = random.choice([
pose = random.choice([
{ "x": 0., "y": 0., "z": 0.087, "w": 0.996 },
{ "x": 0., "y": 0., "z": -0.131, "w": 0.991 }
])
status["location"] = {"x": math.cos(now) * r, "y": math.sin(now) * r, "z": 0, "angle": angle, "planarDatum": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"}
status["location"] = {"x": math.cos(now) * r, "y": math.sin(now) * r, "z": 0, "pose": pose, "planarDatum": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"}

# Generate random paths and destinations
side = random.choice([10, 20, 30])
status["path"] = [
{"timestamp": (nowDt+timedelta(seconds=10)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": 0, "angle": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=20)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": side, "angle": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=30)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": side, "y": side, "angle": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=40)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": side, "y": 0, "angle": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=50)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": 0, "angle": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"}
{"timestamp": (nowDt+timedelta(seconds=10)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": 0, "pose": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=20)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": side, "pose": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=30)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": side, "y": side, "pose": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=40)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": side, "y": 0, "pose": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=50)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": 0, "pose": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"}
]
status["destinations"] = [
{"timestamp": (nowDt+timedelta(seconds=30)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": side, "y": side, "angle": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=50)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": 0, "angle": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"}
{"timestamp": (nowDt+timedelta(seconds=30)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": side, "y": side, "pose": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"},
{"timestamp": (nowDt+timedelta(seconds=50)).strftime("%Y-%m-%dT%H:%M:%S%z"), "x": 0, "y": 0, "pose": { "x": 0., "y": 0., "z": 0., "w": 1 }, "planarDatumUUID": "4B8302DA-21AD-401F-AF45-1DFD956B80B5"}
]

# Send the report message
Expand Down
20 changes: 10 additions & 10 deletions examples/identityReport1.json
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
{
"uuid": "6948DF80-14BD-4E04-8842-7668D9C001F5",
"timestamp": "2012-04-21T18:25:43-05:00",
"manufacturerName": "Mass Robotics AMR",
"robotModel" : "AMR-01",
"robotSerialNumber" : "0000001",
"baseRobotEnvelope" : {
"x" : 0.5,
"y" : 1
}
}
"uuid": "6948DF80-14BD-4E04-8842-7668D9C001F5",
"timestamp": "2012-04-21T18:25:43-05:00",
"manufacturerName": "Mass Robotics AMR",
"robotModel" : "AMR-01",
"robotSerialNumber" : "0000001",
"baseRobotEnvelope" : {
"x" : 0.5,
"y" : 1
}
}
28 changes: 14 additions & 14 deletions examples/statusReport1.json
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
{
"uuid": "6948DF80-14BD-4E04-8842-7668D9C001F5",
"timestamp": "2012-04-21T18:25:43-05:00",
"operationalState": "navigating",
"location" : {
"x" : 0.5,
"y" : 1,
"angle" : {
"w" : 0.924,
"x" : 0.000,
"y" : 0.000,
"z" : 0.383
},
"planarDatum":"4B8302DA-21AD-401F-AF45-1DFD956B80B5"
}
"uuid": "6948DF80-14BD-4E04-8842-7668D9C001F5",
"timestamp": "2012-04-21T18:25:43-05:00",
"operationalState": "navigating",
"location" : {
"x" : 0.5,
"y" : 1,
"pose" : {
"w" : 0.924,
"x" : 0.000,
"y" : 0.000,
"z" : 0.383
},
"planarDatum":"4B8302DA-21AD-401F-AF45-1DFD956B80B5"
}
}