Skip to content

MiR REST API reference

MIR100 REST API

This API does not contain every endpoint in the MiR100 REST API! It contains only endpoints useful to the author at the time of development.

Instructions: Don't forget to set login credentials for the robot REST authorization header. Don't forget to set the robot IP if using other network than MiR100 internal hotspot.

Two ways of sending REST requests:

  • handle_request(): send direct REST request to the robot API
  • handle_request_ros(): send REST request over ROS service. Requires ROS service server node running

MirRestApi

MiR REST API class

Parameters:

Name Type Description Default
usrname str

MiR interface username. Used to generate authorization header.

required
password str

MiR interface password. Used to generate authorization header.

required
ip str

robot IP, defaults to "192.168.12.20"

'192.168.12.20'
Source code in docs/MiR100/mir_rest_api/api.py
  28
  29
  30
  31
  32
  33
  34
  35
  36
  37
  38
  39
  40
  41
  42
  43
  44
  45
  46
  47
  48
  49
  50
  51
  52
  53
  54
  55
  56
  57
  58
  59
  60
  61
  62
  63
  64
  65
  66
  67
  68
  69
  70
  71
  72
  73
  74
  75
  76
  77
  78
  79
  80
  81
  82
  83
  84
  85
  86
  87
  88
  89
  90
  91
  92
  93
  94
  95
  96
  97
  98
  99
 100
 101
 102
 103
 104
 105
 106
 107
 108
 109
 110
 111
 112
 113
 114
 115
 116
 117
 118
 119
 120
 121
 122
 123
 124
 125
 126
 127
 128
 129
 130
 131
 132
 133
 134
 135
 136
 137
 138
 139
 140
 141
 142
 143
 144
 145
 146
 147
 148
 149
 150
 151
 152
 153
 154
 155
 156
 157
 158
 159
 160
 161
 162
 163
 164
 165
 166
 167
 168
 169
 170
 171
 172
 173
 174
 175
 176
 177
 178
 179
 180
 181
 182
 183
 184
 185
 186
 187
 188
 189
 190
 191
 192
 193
 194
 195
 196
 197
 198
 199
 200
 201
 202
 203
 204
 205
 206
 207
 208
 209
 210
 211
 212
 213
 214
 215
 216
 217
 218
 219
 220
 221
 222
 223
 224
 225
 226
 227
 228
 229
 230
 231
 232
 233
 234
 235
 236
 237
 238
 239
 240
 241
 242
 243
 244
 245
 246
 247
 248
 249
 250
 251
 252
 253
 254
 255
 256
 257
 258
 259
 260
 261
 262
 263
 264
 265
 266
 267
 268
 269
 270
 271
 272
 273
 274
 275
 276
 277
 278
 279
 280
 281
 282
 283
 284
 285
 286
 287
 288
 289
 290
 291
 292
 293
 294
 295
 296
 297
 298
 299
 300
 301
 302
 303
 304
 305
 306
 307
 308
 309
 310
 311
 312
 313
 314
 315
 316
 317
 318
 319
 320
 321
 322
 323
 324
 325
 326
 327
 328
 329
 330
 331
 332
 333
 334
 335
 336
 337
 338
 339
 340
 341
 342
 343
 344
 345
 346
 347
 348
 349
 350
 351
 352
 353
 354
 355
 356
 357
 358
 359
 360
 361
 362
 363
 364
 365
 366
 367
 368
 369
 370
 371
 372
 373
 374
 375
 376
 377
 378
 379
 380
 381
 382
 383
 384
 385
 386
 387
 388
 389
 390
 391
 392
 393
 394
 395
 396
 397
 398
 399
 400
 401
 402
 403
 404
 405
 406
 407
 408
 409
 410
 411
 412
 413
 414
 415
 416
 417
 418
 419
 420
 421
 422
 423
 424
 425
 426
 427
 428
 429
 430
 431
 432
 433
 434
 435
 436
 437
 438
 439
 440
 441
 442
 443
 444
 445
 446
 447
 448
 449
 450
 451
 452
 453
 454
 455
 456
 457
 458
 459
 460
 461
 462
 463
 464
 465
 466
 467
 468
 469
 470
 471
 472
 473
 474
 475
 476
 477
 478
 479
 480
 481
 482
 483
 484
 485
 486
 487
 488
 489
 490
 491
 492
 493
 494
 495
 496
 497
 498
 499
 500
 501
 502
 503
 504
 505
 506
 507
 508
 509
 510
 511
 512
 513
 514
 515
 516
 517
 518
 519
 520
 521
 522
 523
 524
 525
 526
 527
 528
 529
 530
 531
 532
 533
 534
 535
 536
 537
 538
 539
 540
 541
 542
 543
 544
 545
 546
 547
 548
 549
 550
 551
 552
 553
 554
 555
 556
 557
 558
 559
 560
 561
 562
 563
 564
 565
 566
 567
 568
 569
 570
 571
 572
 573
 574
 575
 576
 577
 578
 579
 580
 581
 582
 583
 584
 585
 586
 587
 588
 589
 590
 591
 592
 593
 594
 595
 596
 597
 598
 599
 600
 601
 602
 603
 604
 605
 606
 607
 608
 609
 610
 611
 612
 613
 614
 615
 616
 617
 618
 619
 620
 621
 622
 623
 624
 625
 626
 627
 628
 629
 630
 631
 632
 633
 634
 635
 636
 637
 638
 639
 640
 641
 642
 643
 644
 645
 646
 647
 648
 649
 650
 651
 652
 653
 654
 655
 656
 657
 658
 659
 660
 661
 662
 663
 664
 665
 666
 667
 668
 669
 670
 671
 672
 673
 674
 675
 676
 677
 678
 679
 680
 681
 682
 683
 684
 685
 686
 687
 688
 689
 690
 691
 692
 693
 694
 695
 696
 697
 698
 699
 700
 701
 702
 703
 704
 705
 706
 707
 708
 709
 710
 711
 712
 713
 714
 715
 716
 717
 718
 719
 720
 721
 722
 723
 724
 725
 726
 727
 728
 729
 730
 731
 732
 733
 734
 735
 736
 737
 738
 739
 740
 741
 742
 743
 744
 745
 746
 747
 748
 749
 750
 751
 752
 753
 754
 755
 756
 757
 758
 759
 760
 761
 762
 763
 764
 765
 766
 767
 768
 769
 770
 771
 772
 773
 774
 775
 776
 777
 778
 779
 780
 781
 782
 783
 784
 785
 786
 787
 788
 789
 790
 791
 792
 793
 794
 795
 796
 797
 798
 799
 800
 801
 802
 803
 804
 805
 806
 807
 808
 809
 810
 811
 812
 813
 814
 815
 816
 817
 818
 819
 820
 821
 822
 823
 824
 825
 826
 827
 828
 829
 830
 831
 832
 833
 834
 835
 836
 837
 838
 839
 840
 841
 842
 843
 844
 845
 846
 847
 848
 849
 850
 851
 852
 853
 854
 855
 856
 857
 858
 859
 860
 861
 862
 863
 864
 865
 866
 867
 868
 869
 870
 871
 872
 873
 874
 875
 876
 877
 878
 879
 880
 881
 882
 883
 884
 885
 886
 887
 888
 889
 890
 891
 892
 893
 894
 895
 896
 897
 898
 899
 900
 901
 902
 903
 904
 905
 906
 907
 908
 909
 910
 911
 912
 913
 914
 915
 916
 917
 918
 919
 920
 921
 922
 923
 924
 925
 926
 927
 928
 929
 930
 931
 932
 933
 934
 935
 936
 937
 938
 939
 940
 941
 942
 943
 944
 945
 946
 947
 948
 949
 950
 951
 952
 953
 954
 955
 956
 957
 958
 959
 960
 961
 962
 963
 964
 965
 966
 967
 968
 969
 970
 971
 972
 973
 974
 975
 976
 977
 978
 979
 980
 981
 982
 983
 984
 985
 986
 987
 988
 989
 990
 991
 992
 993
 994
 995
 996
 997
 998
 999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
class MirRestApi:
    """MiR REST API class

    :param usrname: MiR interface username. Used to generate authorization header.
    :type usrname: str
    :param password: MiR interface password. Used to generate authorization header.
    :type password: str
    :param ip: robot IP, defaults to "192.168.12.20"
    :type ip: str, optional
    """

    def __init__(self, usrname: str, password: str, ip: str = "192.168.12.20") -> None:
        self.url = "http://" + ip + "/api/v2.0.0"
        self.header = {
            'Content-Type': 'application/json',
            'Authorization': self.generate_auth_head(usrname, password)
            }

        # when sending requests over ROS services we need a service handle
        self.service_handle = rospy.ServiceProxy('mir_rest_api_service', Rest)

    def generate_auth_head(self, usrname: str, password: str) -> str:
        """generate authorization header

        :param usrname: MiR interface username
        :type usrname: str
        :param password: MiR interface password
        :type password: str
        :return: authorization string
        :rtype: str
        """

        hashed_pass = hashlib.sha256(password.encode('utf-8')).hexdigest()
        string = usrname + ":" + hashed_pass
        string_bytes = string.encode("ascii")
        base64_bytes = base64.b64encode(string_bytes)
        base64_string = base64_bytes.decode("ascii")
        auth_header = "Basic " + base64_string
        return auth_header

    def handle_request(self) -> [int, dict]:
        """Handle REST request

        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        if self.method == "GET":
            try:
                response = requests.get(self.endpoint, headers=self.header)
                response = [response.status_code, response.json()]
                return response
            except Exception as e:
                # rospy.logerr(e)
                print(e) 

        elif self.method == "DELETE":
            try:
                response = requests.delete(self.endpoint, headers=self.header)
                response = [response.status_code, {}]
                return response
            except Exception as e:
                # rospy.logerr(e)
                print(e) 

        elif self.method == "POST":
            try:
                response = requests.post(self.endpoint, json=self.json, headers=self.header)
                response = [response.status_code, response.json()]
                # if response[0] != 200:
                #     pprint(response[1])
                return response
            except Exception as e:
                # rospy.logerr(e)
                print(e) 

        elif self.method == "PUT":
            try:
                response = requests.put(self.endpoint, json=self.json, headers=self.header)
                response = [response.status_code, response.json()]
                # if response[0] != 200:
                #     pprint(response[1])
                return response
            except Exception as e:
                # rospy.logerr(e)
                print(e)  

        else:
            # rospy.loginfo("Incorrect REST method!")
            print("Incorrect REST method!")

    def handle_request_ros(self) -> RestResponse:
        """Handle REST request over ROS service. Needs ROS service server node running

        :return: ROS service response containing REST response status code and body
        :rtype: RestResponse
        """

        try:
            response = self.service_handle(self.method, json.dumps(self.header), self.endpoint, json.dumps(self.json))
            response = [response.status_code, json.loads(response.response)]
            return response
        except rospy.ServiceException as e:
            rospy.logerr(e)


    # MiR REST API endpoints:
    # -------- robot settings ---------
    def settings_groups_get(self, ros: bool = 0) -> [int, List[dict]]:
        """Retrieve a list with the settings groups

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int, List[dict]]
        """

        self.method = "GET"
        self.endpoint = self.url + "/setting_groups"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def settings_groups_id_get(self, group_id: int, ros: bool = 0) -> [int, List[dict]]:
        """Retrieve the list of settings from the settings group with the specified settings group ID

        :param group_id: settings group ID
        :type group_id: int
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int, List[dict]]
        """

        self.method = "GET"
        self.endpoint = self.url + "/setting_groups/" + str(group_id) + "/settings"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def settings_groups_name_get(self, group_name: str, ros: bool = 0) -> [int, List[dict]]:
        """Retrieve the list of settings from the settings group with the specified settings group name

        :param group_name: settings group name
        :type group_name: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int, List[dict]]
        """

        groups = self.settings_groups_get(ros)
        setting_group = next(item for item in groups[1] if item["name"] == group_name)
        setting_group = self.settings_groups_id_get(setting_group["id"],ros)
        return setting_group

    def setting_name_get(self, group_name: str, setting_name: str, ros: bool = 0) -> [int,dict]:
        """Retrieve the details of the setting with the specified settings group name and setting name

        :param group_name: settings group name
        :type group_name: str
        :param setting_name: setting name
        :type setting_name: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int,dict]
        """

        settings_list = self.settings_groups_name_get(group_name,ros)
        setting = next(item for item in settings_list[1] if item["name"] == setting_name)
        return [settings_list[0], setting]

    def setting_name_put(self, group_name: str, setting_name: str, setting_value: str, ros: bool = 0) -> [int,dict]:

        setting_id = self.setting_name_get(group_name, setting_name, ros)[1]["id"]

        self.method = "PUT"
        self.endpoint = self.url + "/settings/" + str(setting_id)
        self.json = {"value": str(setting_value)}
        if ros == 1:
            response =  self.handle_request_ros()
            return [response[0], {"name": response[1]["name"],"value": response[1]["value"]}]
        else:
            response =  self.handle_request()
            return [response[0], {"name": response[1]["name"],"value": response[1]["value"]}]

    # ---------- robot state ----------
    def status_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the robot status

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/status"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def status_put(self, json: dict, ros: bool = 0) -> [int, dict]:
        """Modify the robot status

        :param json: request body
        :type json: dict
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "PUT"
        self.endpoint = self.url + "/status"
        self.json = json
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def status_mode_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the current mode of the robot

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/status"
        self.json = ""
        if ros == 1:
            response =  self.handle_request_ros()
            return [response[0], {"mode_id": response[1]["mode_id"],"mode_text": response[1]["mode_text"], "mode_key_state":response[1]["mode_key_state"]}]
        else:
            response =  self.handle_request()
            return [response[0], {"mode_id": response[1]["mode_id"],"mode_text": response[1]["mode_text"], "mode_key_state":response[1]["mode_key_state"]}]

    def status_state_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the current state of the robot

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/status"
        self.json = ""
        if ros == 1:
            response =  self.handle_request_ros()
            return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]
        else:
            response =  self.handle_request()
            return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]

    def status_state_id_put(self, state_id: int, ros: bool = 0) -> [int, dict]:
        """Modify the current state of the robot. 

        Possible robot state_id: {3, 4, 5, 11}, State: {Ready, Pause, Executing,Manual control}.
        Using this method the user can only put state_id: {3, 4}, State: {Ready, Pause}.

        :param state_id: desired robot state
        :type state_id: int
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        if state_id !=3 and state_id != 4:
            print("INVALID INPUT. Select state_id=3 for 'Ready' or state_id=4 for 'Pause'")
            return

        self.method = "PUT"
        self.endpoint = self.url + "/status"
        self.json = {"state_id" : state_id}
        if ros == 1:
            response =  self.handle_request_ros()
            return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]
        else:
            response =  self.handle_request()
            return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]


    def status_state_id_toggle_put(self, ros: bool = 0) -> [int, dict]:
        """Toggle the current state of the robot between 'Ready'/'Executing' and 'Pause'.

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        status = self.status_state_get(ros)[1]
        if status["state_id"] == 3:
            state_id = 4
            # rospy.loginfo("Setting the robot state to: 'Pause'")
            print("Robot is in state: 'Ready'. Setting the robot state to: 'Pause'")
        elif status["state_id"] == 4:
            state_id = 3
            # rospy.loginfo("Setting the robot state to: 'Ready'")
            print("Robot is in state: 'Pause'. Setting the robot state to: 'Ready'/'Executing'")
        elif status ["state_id"] == 5:
            state_id = 4
            # rospy.loginfo("Setting the robot state to: 'Ready'")
            print("Robot is in state: 'Executing'. Setting the robot state to: 'Pause'")
        elif status ["state_id"] == 10:
            # rospy.loginfo("Setting the robot state to: 'Ready'")
            print("Robot is in state: 'EmergencyStop'. Unable to toggle robot status")
            return
        else:
            # rospy.logerr("Unable to toggle robot status")
            print("Unable to toggle robot status")
            return

        self.method = "PUT"
        self.endpoint = self.url + "/status"
        self.json = {"state_id" : state_id}
        if ros == 1:
            response =  self.handle_request_ros()
            return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]
        else:
            response =  self.handle_request()
            return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]

    # ---------- missions ----------
    def mission_groups_get(self, ros: bool = 0) -> [int, List[dict]]:
        """Retrieve the list of mission groups

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, List[dict]]
        """

        self.method = "GET"
        self.endpoint = self.url + "/mission_groups"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def mission_groups_group_id_missions_get(self, group_id: str, ros: bool = 0) -> [int, List[dict]]:
        """Retrieve the list of missions that belong to the group with the specified group ID

        :param group_id: mission group ID
        :type group_id: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, List[dict]]
        """

        self.method = "GET"
        self.endpoint = self.url + "/mission_groups/" + group_id + "/missions"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_groups_group_name_missions_get(self, group_name: str, ros: bool = 0) -> [int, List[dict]]:
        """Retrieve the list of missions that belong to the group with the specified group name

        :param group_name: missions group name
        :type group_name: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int, List[dict]]
        """

        mission_groups = self.mission_groups_get(ros)
        group = next(item for item in mission_groups[1] if item["name"] == str(group_name))
        group_guid = group["guid"]

        missions = self.mission_groups_group_id_missions_get(group_guid, ros)
        return missions

    def missions_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of missions

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/missions"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_guid_get(self, guid: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the details about the mission with the specified GUID

        :param guid: mission GUID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/missions/" + guid
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_guid_delete(self, guid: str, ros: bool = 0) -> [int, dict]:
        """Erase the mission with the specified GUID

        :param guid: mission GUID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "DELETE"
        self.endpoint = self.url + "/missions/" + guid
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_guid_definition_get(self, guid: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the mission with the specified GUID as an action definition that can be inserted in another mission

        :param guid: mission GUID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/missions/" + guid + "/definition"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_mission_id_actions_get(self, mission_id: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of actions that belong to the mission with the specified mission ID

        :param mission_id: mission ID
        :type mission_id: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/missions/" + mission_id + "/actions"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_mission_id_actions_guid_get(self, mission_id: str, guid: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the details about the action with the specified GUID that belongs to the mission with the specified mission ID

        :param mission_id: mission ID
        :type mission_id: str
        :param guid: action GUID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/missions/" + mission_id + "/actions/" + guid
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_mission_id_actions_guid_put(self, mission_id: str, guid: str, action_msg, ros: bool = 0) -> [int, dict]:
        """Modify the values of the action with the specified GUID that belongs to the mission with the specified mission ID

        :param mission_id: mission ID
        :type mission_id: str
        :param guid: action GUID
        :type guid: str
        :param action_msg: MiR action body
        :type action_msg: json
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "PUT"
        self.endpoint = self.url + "/missions/" + mission_id + "/actions/" + guid
        self.json = action_msg
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def missions_mission_id_actions_guid_delete(self, mission_id: str, guid: str, ros: bool = 0) -> [int, dict]:
        """Erase the action with the specified GUID from the mission with the specified mission ID

        :param mission_id: mission ID
        :type mission_id: str
        :param guid: action GUID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "DELETE"
        self.endpoint = self.url + "/missions/" + mission_id + "/actions/" + guid
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    # ---------- mission queue ----------
    def mission_queue_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of missions in the queue. Finished, failed, pending and executing missions will be displayed here

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/mission_queue"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def mission_queue_post(self, mission_id: str, ros: bool = 0) -> [int, dict]:
        """Add a new mission to the mission queue. The mission will always go to the end of the queue

        :param mission_id: mission ID
        :type mission_id: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "POST"
        self.endpoint = self.url + "/mission_queue"
        self.json = {"mission_id": mission_id}
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def mission_queue_delete(self, ros: bool = 0) -> [int, dict]:
        """Abort all the pending and executing missions from the mission queue

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "DELETE"
        self.endpoint = self.url + "/mission_queue"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def mission_queue_id_get(self, id: int, ros: bool = 0) -> [int, dict]:
        """Retrieve the details about the mission with the specified ID in the mission queue

        :param id: mission ID in the mission queue
        :type id: int
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/mission_queue/" + str(id)
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def mission_queue_id_delete(self, id: int, ros: bool = 0) -> [int, dict]:
        """Abort the mission with the specified ID in the mission queue

        :param id: mission ID in the mission queue
        :type id: int
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "DELETE"
        self.endpoint = self.url + "/mission_queue/" + str(id)
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def mission_queue_mission_queue_id_actions_get(self, mission_queue_id: int, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of actions from the mission with the specified ID in the mission queue

        :param mission_queue_id: mission ID in the mission queue
        :type mission_queue_id: int
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/mission_queue/" + str(mission_queue_id) + "/actions"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def mission_queue_mission_queue_id_actions_id_get(self, mission_queue_id: int, id: int, ros: bool = 0) -> [int, dict]:
        """Retrieve the details about the action with the specified ID from the mission with the specified ID in the mission queue

        :param mission_queue_id: mission ID in the mission queue
        :type mission_queue_id: int
        :param id: action ID
        :type id: int
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/mission_queue/" + str(mission_queue_id) + "/actions/" + str(id)
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    # ---------- maps----------
    def maps_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of maps

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/maps"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def sessions_session_id_maps_get(self, session_id: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of maps that belong to the session with the specified session ID. session_id = site_id

        :param session_id: site ID
        :type session_id: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/sessions/" + session_id + "/maps"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def maps_guid_get(self, guid: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the details about the map with the specified GUID

        :param guid: map GUID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/maps/" + guid
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def maps_guid_delete(self, guid: str, ros: bool = 0) -> [int, dict]:
        """Erase the map with the specified GUID

        :param guid: map GUID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "DELETE"
        self.endpoint = self.url + "/maps/" + guid
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    # ---------- positions ----------
    def positions_post(self, position, ros: bool = 0) -> [int, dict]: 
        """Add a new position.

        Position json needs to have at least: {name, pos_x, pos_y, orientation, type_id, map_id}

        :param position: position json
        :type position: json
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int, dict]
        """

        self.method = "POST"
        self.endpoint = self.url + "/positions"
        self.json = position
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def maps_map_id_positions_get(self, map_id: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of positions that belong to the map with the specified map ID

        :param map_id: map ID
        :type map_id: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/maps/" + map_id + "/positions"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def positions_guid_get(self, guid: str, ros: bool = 0) -> [int,dict]:
        """Retrieve the details about the position with the specified GUID

        :param guid: The global id unique across robots that identifies this position
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int,dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/positions/" + guid
        self.json = ""

        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def positions_pos_id_docking_offsets_get(self, pos_id: str, ros: bool = 0) -> [int,dict]:
        """Retrieve the details of the docking offset of the position with the specified position ID

        :param pos_id: position ID
        :type pos_id: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int,dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/positions/" + pos_id + "/docking_offsets"
        self.json = ""

        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def position_transition_lists_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of position transition lists

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/position_transition_lists"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def position_types_id_get(self, id: str, ros: bool = 0) -> [int,dict]:
        """Retrieve the details about the position type with the specified type ID

        :param guid: position type ID
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int,dict]
        """

        """ Position Types:
        {'id': 0, 'name': 'Robot position', 'url': '/v2.0.0/position_types/0'},
        {'id': 1, 'name': 'Cart position', 'url': '/v2.0.0/position_types/1'},
        {'id': 2, 'name': 'Cart pickup position', 'url': '/v2.0.0/position_types/2'},
        {'id': 3, 'name': 'Cart left entry', 'url': '/v2.0.0/position_types/3'},
        {'id': 4, 'name': 'Cart right entry', 'url': '/v2.0.0/position_types/4'},
        {'id': 5, 'name': 'Shelf position', 'url': '/v2.0.0/position_types/5'},
        {'id': 6, 'name': 'Shelf short entry position', 'url': '/v2.0.0/position_types/6'},
        {'id': 7, 'name': 'MiRCharge 100/200', 'url': '/v2.0.0/position_types/7'},
        {'id': 8, 'name': 'MiRCharge 100/200 entry', 'url': '/v2.0.0/position_types/8'},
        {'id': 9, 'name': 'V-marker', 'url': '/v2.0.0/position_types/9'},
        {'id': 10, 'name': 'V-marker entry', 'url': '/v2.0.0/position_types/10'},
        {'id': 11, 'name': 'VL-marker', 'url': '/v2.0.0/position_types/11'},
        {'id': 12, 'name': 'VL-marker entry', 'url': '/v2.0.0/position_types/12'},
        {'id': 13, 'name': 'L-marker', 'url': '/v2.0.0/position_types/13'},
        {'id': 14, 'name': 'L-marker entry', 'url': '/v2.0.0/position_types/14'},
        {'id': 15, 'name': 'Emergency position', 'url': '/v2.0.0/position_types/15'},
        {'id': 16, 'name': 'Precision marker', 'url': '/v2.0.0/position_types/16'},
        {'id': 17, 'name': 'Precision marker entry', 'url': '/v2.0.0/position_types/17'},
        {'id': 18, 'name': 'Pallet rack', 'url': '/v2.0.0/position_types/18'},
        {'id': 19, 'name': 'Pallet rack entry position', 'url': '/v2.0.0/position_types/19'},
        {'id': 20, 'name': 'MiRCharge 500/1000', 'url': '/v2.0.0/position_types/20'},
        {'id': 21, 'name': 'MiRCharge 500/1000 entry', 'url': '/v2.0.0/position_types/21'},
        {'id': 22, 'name': 'Bar-marker', 'url': '/v2.0.0/position_types/22'},
        {'id': 23, 'name': 'Bar-marker entry', 'url': '/v2.0.0/position_types/23'},
        {'id': 25, 'name': 'elevator position', 'url': '/v2.0.0/position_types/25'},
        {'id': 26, 'name': 'elevator entry position', 'url': '/v2.0.0/position_types/26'},
        {'id': 42, 'name': 'Staging position', 'url': '/v2.0.0/position_types/42'},
        {'id': 106, 'name': 'Shelf long entry position', 'url': '/v2.0.0/position_types/106'}]]
        """

        self.method = "GET"
        self.endpoint = self.url + "/position_types/" + id
        self.json = ""

        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def position_types_get(self, ros: bool = 0) -> [int,dict]:
        """Retrieve a list of possible position types

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: [int,dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/position_types"
        self.json = ""

        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    # ---------- actions ----------
    def actions_get(self, ros: bool = 0) -> [int, dict]:
        """Retrieve the list of action definitions

        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/actions"
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def actions_action_type_get(self, action_type: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the details about the action type. It displays the parameters of the action and the limits for the values among others

        :param action_type: action type
        :type action_type: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/actions/" + action_type 
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    # ---------- docking offsets ----------
    def docking_offsets_guid_get(self, guid: str, ros: bool = 0) -> [int, dict]:
        """Retrieve the details of the docking offset with the specified GUID

        :param guid: action docking offset guid
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "GET"
        self.endpoint = self.url + "/docking_offsets/" + guid 
        self.json = ""
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

    def docking_offsets_guid_put(self, guid: str, offsets, ros: bool = 0) -> [int, dict]:
        """Modify the values of the docking offset with the specified GUID

        :param guid: action docking offset guid
        :type guid: str
        :param ros: use ROS service, defaults to 0
        :type ros: bool, optional
        :return: a list containing REST response status code and body
        :rtype: list[int, dict]
        """

        self.method = "PUT"
        self.endpoint = self.url + "/docking_offsets/" + guid 
        self.json = offsets
        if ros == 1:
            return self.handle_request_ros()
        else:
            return self.handle_request()

actions_action_type_get(action_type, ros=0)

Retrieve the details about the action type. It displays the parameters of the action and the limits for the values among others

Parameters:

Name Type Description Default
action_type str

action type

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
def actions_action_type_get(self, action_type: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the details about the action type. It displays the parameters of the action and the limits for the values among others

    :param action_type: action type
    :type action_type: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/actions/" + action_type 
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

actions_get(ros=0)

Retrieve the list of action definitions

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
def actions_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of action definitions

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/actions"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

docking_offsets_guid_get(guid, ros=0)

Retrieve the details of the docking offset with the specified GUID

Parameters:

Name Type Description Default
guid str

action docking offset guid

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
 989
 990
 991
 992
 993
 994
 995
 996
 997
 998
 999
1000
1001
1002
1003
1004
1005
1006
def docking_offsets_guid_get(self, guid: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the details of the docking offset with the specified GUID

    :param guid: action docking offset guid
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/docking_offsets/" + guid 
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

docking_offsets_guid_put(guid, offsets, ros=0)

Modify the values of the docking offset with the specified GUID

Parameters:

Name Type Description Default
guid str

action docking offset guid

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
def docking_offsets_guid_put(self, guid: str, offsets, ros: bool = 0) -> [int, dict]:
    """Modify the values of the docking offset with the specified GUID

    :param guid: action docking offset guid
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "PUT"
    self.endpoint = self.url + "/docking_offsets/" + guid 
    self.json = offsets
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

generate_auth_head(usrname, password)

generate authorization header

Parameters:

Name Type Description Default
usrname str

MiR interface username

required
password str

MiR interface password

required

Returns:

Type Description
str

authorization string

Source code in docs/MiR100/mir_rest_api/api.py
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
def generate_auth_head(self, usrname: str, password: str) -> str:
    """generate authorization header

    :param usrname: MiR interface username
    :type usrname: str
    :param password: MiR interface password
    :type password: str
    :return: authorization string
    :rtype: str
    """

    hashed_pass = hashlib.sha256(password.encode('utf-8')).hexdigest()
    string = usrname + ":" + hashed_pass
    string_bytes = string.encode("ascii")
    base64_bytes = base64.b64encode(string_bytes)
    base64_string = base64_bytes.decode("ascii")
    auth_header = "Basic " + base64_string
    return auth_header

handle_request()

Handle REST request

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
def handle_request(self) -> [int, dict]:
    """Handle REST request

    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    if self.method == "GET":
        try:
            response = requests.get(self.endpoint, headers=self.header)
            response = [response.status_code, response.json()]
            return response
        except Exception as e:
            # rospy.logerr(e)
            print(e) 

    elif self.method == "DELETE":
        try:
            response = requests.delete(self.endpoint, headers=self.header)
            response = [response.status_code, {}]
            return response
        except Exception as e:
            # rospy.logerr(e)
            print(e) 

    elif self.method == "POST":
        try:
            response = requests.post(self.endpoint, json=self.json, headers=self.header)
            response = [response.status_code, response.json()]
            # if response[0] != 200:
            #     pprint(response[1])
            return response
        except Exception as e:
            # rospy.logerr(e)
            print(e) 

    elif self.method == "PUT":
        try:
            response = requests.put(self.endpoint, json=self.json, headers=self.header)
            response = [response.status_code, response.json()]
            # if response[0] != 200:
            #     pprint(response[1])
            return response
        except Exception as e:
            # rospy.logerr(e)
            print(e)  

    else:
        # rospy.loginfo("Incorrect REST method!")
        print("Incorrect REST method!")

handle_request_ros()

Handle REST request over ROS service. Needs ROS service server node running

Returns:

Type Description
RestResponse

ROS service response containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
119
120
121
122
123
124
125
126
127
128
129
130
131
def handle_request_ros(self) -> RestResponse:
    """Handle REST request over ROS service. Needs ROS service server node running

    :return: ROS service response containing REST response status code and body
    :rtype: RestResponse
    """

    try:
        response = self.service_handle(self.method, json.dumps(self.header), self.endpoint, json.dumps(self.json))
        response = [response.status_code, json.loads(response.response)]
        return response
    except rospy.ServiceException as e:
        rospy.logerr(e)

maps_get(ros=0)

Retrieve the list of maps

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
def maps_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of maps

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/maps"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

maps_guid_delete(guid, ros=0)

Erase the map with the specified GUID

Parameters:

Name Type Description Default
guid str

map GUID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
def maps_guid_delete(self, guid: str, ros: bool = 0) -> [int, dict]:
    """Erase the map with the specified GUID

    :param guid: map GUID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "DELETE"
    self.endpoint = self.url + "/maps/" + guid
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

maps_guid_get(guid, ros=0)

Retrieve the details about the map with the specified GUID

Parameters:

Name Type Description Default
guid str

map GUID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
def maps_guid_get(self, guid: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the details about the map with the specified GUID

    :param guid: map GUID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/maps/" + guid
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

maps_map_id_positions_get(map_id, ros=0)

Retrieve the list of positions that belong to the map with the specified map ID

Parameters:

Name Type Description Default
map_id str

map ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
def maps_map_id_positions_get(self, map_id: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of positions that belong to the map with the specified map ID

    :param map_id: map ID
    :type map_id: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/maps/" + map_id + "/positions"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_groups_get(ros=0)

Retrieve the list of mission groups

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, List[dict]]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
def mission_groups_get(self, ros: bool = 0) -> [int, List[dict]]:
    """Retrieve the list of mission groups

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, List[dict]]
    """

    self.method = "GET"
    self.endpoint = self.url + "/mission_groups"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_groups_group_id_missions_get(group_id, ros=0)

Retrieve the list of missions that belong to the group with the specified group ID

Parameters:

Name Type Description Default
group_id str

mission group ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, List[dict]]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
def mission_groups_group_id_missions_get(self, group_id: str, ros: bool = 0) -> [int, List[dict]]:
    """Retrieve the list of missions that belong to the group with the specified group ID

    :param group_id: mission group ID
    :type group_id: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, List[dict]]
    """

    self.method = "GET"
    self.endpoint = self.url + "/mission_groups/" + group_id + "/missions"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_queue_delete(ros=0)

Abort all the pending and executing missions from the mission queue

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
def mission_queue_delete(self, ros: bool = 0) -> [int, dict]:
    """Abort all the pending and executing missions from the mission queue

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "DELETE"
    self.endpoint = self.url + "/mission_queue"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_queue_get(ros=0)

Retrieve the list of missions in the queue. Finished, failed, pending and executing missions will be displayed here

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
def mission_queue_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of missions in the queue. Finished, failed, pending and executing missions will be displayed here

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/mission_queue"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_queue_id_delete(id, ros=0)

Abort the mission with the specified ID in the mission queue

Parameters:

Name Type Description Default
id int

mission ID in the mission queue

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
def mission_queue_id_delete(self, id: int, ros: bool = 0) -> [int, dict]:
    """Abort the mission with the specified ID in the mission queue

    :param id: mission ID in the mission queue
    :type id: int
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "DELETE"
    self.endpoint = self.url + "/mission_queue/" + str(id)
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_queue_id_get(id, ros=0)

Retrieve the details about the mission with the specified ID in the mission queue

Parameters:

Name Type Description Default
id int

mission ID in the mission queue

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
def mission_queue_id_get(self, id: int, ros: bool = 0) -> [int, dict]:
    """Retrieve the details about the mission with the specified ID in the mission queue

    :param id: mission ID in the mission queue
    :type id: int
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/mission_queue/" + str(id)
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_queue_mission_queue_id_actions_get(mission_queue_id, ros=0)

Retrieve the list of actions from the mission with the specified ID in the mission queue

Parameters:

Name Type Description Default
mission_queue_id int

mission ID in the mission queue

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
def mission_queue_mission_queue_id_actions_get(self, mission_queue_id: int, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of actions from the mission with the specified ID in the mission queue

    :param mission_queue_id: mission ID in the mission queue
    :type mission_queue_id: int
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/mission_queue/" + str(mission_queue_id) + "/actions"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_queue_mission_queue_id_actions_id_get(mission_queue_id, id, ros=0)

Retrieve the details about the action with the specified ID from the mission with the specified ID in the mission queue

Parameters:

Name Type Description Default
mission_queue_id int

mission ID in the mission queue

required
id int

action ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
def mission_queue_mission_queue_id_actions_id_get(self, mission_queue_id: int, id: int, ros: bool = 0) -> [int, dict]:
    """Retrieve the details about the action with the specified ID from the mission with the specified ID in the mission queue

    :param mission_queue_id: mission ID in the mission queue
    :type mission_queue_id: int
    :param id: action ID
    :type id: int
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/mission_queue/" + str(mission_queue_id) + "/actions/" + str(id)
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

mission_queue_post(mission_id, ros=0)

Add a new mission to the mission queue. The mission will always go to the end of the queue

Parameters:

Name Type Description Default
mission_id str

mission ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
def mission_queue_post(self, mission_id: str, ros: bool = 0) -> [int, dict]:
    """Add a new mission to the mission queue. The mission will always go to the end of the queue

    :param mission_id: mission ID
    :type mission_id: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "POST"
    self.endpoint = self.url + "/mission_queue"
    self.json = {"mission_id": mission_id}
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_get(ros=0)

Retrieve the list of missions

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
def missions_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of missions

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/missions"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_groups_group_name_missions_get(group_name, ros=0)

Retrieve the list of missions that belong to the group with the specified group name

Parameters:

Name Type Description Default
group_name str

missions group name

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int, List[dict]]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
def missions_groups_group_name_missions_get(self, group_name: str, ros: bool = 0) -> [int, List[dict]]:
    """Retrieve the list of missions that belong to the group with the specified group name

    :param group_name: missions group name
    :type group_name: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int, List[dict]]
    """

    mission_groups = self.mission_groups_get(ros)
    group = next(item for item in mission_groups[1] if item["name"] == str(group_name))
    group_guid = group["guid"]

    missions = self.mission_groups_group_id_missions_get(group_guid, ros)
    return missions

missions_guid_definition_get(guid, ros=0)

Retrieve the mission with the specified GUID as an action definition that can be inserted in another mission

Parameters:

Name Type Description Default
guid str

mission GUID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
def missions_guid_definition_get(self, guid: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the mission with the specified GUID as an action definition that can be inserted in another mission

    :param guid: mission GUID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/missions/" + guid + "/definition"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_guid_delete(guid, ros=0)

Erase the mission with the specified GUID

Parameters:

Name Type Description Default
guid str

mission GUID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
def missions_guid_delete(self, guid: str, ros: bool = 0) -> [int, dict]:
    """Erase the mission with the specified GUID

    :param guid: mission GUID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "DELETE"
    self.endpoint = self.url + "/missions/" + guid
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_guid_get(guid, ros=0)

Retrieve the details about the mission with the specified GUID

Parameters:

Name Type Description Default
guid str

mission GUID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
def missions_guid_get(self, guid: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the details about the mission with the specified GUID

    :param guid: mission GUID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/missions/" + guid
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_mission_id_actions_get(mission_id, ros=0)

Retrieve the list of actions that belong to the mission with the specified mission ID

Parameters:

Name Type Description Default
mission_id str

mission ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
def missions_mission_id_actions_get(self, mission_id: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of actions that belong to the mission with the specified mission ID

    :param mission_id: mission ID
    :type mission_id: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/missions/" + mission_id + "/actions"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_mission_id_actions_guid_delete(mission_id, guid, ros=0)

Erase the action with the specified GUID from the mission with the specified mission ID

Parameters:

Name Type Description Default
mission_id str

mission ID

required
guid str

action GUID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
def missions_mission_id_actions_guid_delete(self, mission_id: str, guid: str, ros: bool = 0) -> [int, dict]:
    """Erase the action with the specified GUID from the mission with the specified mission ID

    :param mission_id: mission ID
    :type mission_id: str
    :param guid: action GUID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "DELETE"
    self.endpoint = self.url + "/missions/" + mission_id + "/actions/" + guid
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_mission_id_actions_guid_get(mission_id, guid, ros=0)

Retrieve the details about the action with the specified GUID that belongs to the mission with the specified mission ID

Parameters:

Name Type Description Default
mission_id str

mission ID

required
guid str

action GUID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
def missions_mission_id_actions_guid_get(self, mission_id: str, guid: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the details about the action with the specified GUID that belongs to the mission with the specified mission ID

    :param mission_id: mission ID
    :type mission_id: str
    :param guid: action GUID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/missions/" + mission_id + "/actions/" + guid
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

missions_mission_id_actions_guid_put(mission_id, guid, action_msg, ros=0)

Modify the values of the action with the specified GUID that belongs to the mission with the specified mission ID

Parameters:

Name Type Description Default
mission_id str

mission ID

required
guid str

action GUID

required
action_msg json

MiR action body

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
def missions_mission_id_actions_guid_put(self, mission_id: str, guid: str, action_msg, ros: bool = 0) -> [int, dict]:
    """Modify the values of the action with the specified GUID that belongs to the mission with the specified mission ID

    :param mission_id: mission ID
    :type mission_id: str
    :param guid: action GUID
    :type guid: str
    :param action_msg: MiR action body
    :type action_msg: json
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "PUT"
    self.endpoint = self.url + "/missions/" + mission_id + "/actions/" + guid
    self.json = action_msg
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

position_transition_lists_get(ros=0)

Retrieve the list of position transition lists

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
def position_transition_lists_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of position transition lists

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/position_transition_lists"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

position_types_get(ros=0)

Retrieve a list of possible position types

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int,dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
def position_types_get(self, ros: bool = 0) -> [int,dict]:
    """Retrieve a list of possible position types

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int,dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/position_types"
    self.json = ""

    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

position_types_id_get(id, ros=0)

Retrieve the details about the position type with the specified type ID

Parameters:

Name Type Description Default
guid str

position type ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int,dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
def position_types_id_get(self, id: str, ros: bool = 0) -> [int,dict]:
    """Retrieve the details about the position type with the specified type ID

    :param guid: position type ID
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int,dict]
    """

    """ Position Types:
    {'id': 0, 'name': 'Robot position', 'url': '/v2.0.0/position_types/0'},
    {'id': 1, 'name': 'Cart position', 'url': '/v2.0.0/position_types/1'},
    {'id': 2, 'name': 'Cart pickup position', 'url': '/v2.0.0/position_types/2'},
    {'id': 3, 'name': 'Cart left entry', 'url': '/v2.0.0/position_types/3'},
    {'id': 4, 'name': 'Cart right entry', 'url': '/v2.0.0/position_types/4'},
    {'id': 5, 'name': 'Shelf position', 'url': '/v2.0.0/position_types/5'},
    {'id': 6, 'name': 'Shelf short entry position', 'url': '/v2.0.0/position_types/6'},
    {'id': 7, 'name': 'MiRCharge 100/200', 'url': '/v2.0.0/position_types/7'},
    {'id': 8, 'name': 'MiRCharge 100/200 entry', 'url': '/v2.0.0/position_types/8'},
    {'id': 9, 'name': 'V-marker', 'url': '/v2.0.0/position_types/9'},
    {'id': 10, 'name': 'V-marker entry', 'url': '/v2.0.0/position_types/10'},
    {'id': 11, 'name': 'VL-marker', 'url': '/v2.0.0/position_types/11'},
    {'id': 12, 'name': 'VL-marker entry', 'url': '/v2.0.0/position_types/12'},
    {'id': 13, 'name': 'L-marker', 'url': '/v2.0.0/position_types/13'},
    {'id': 14, 'name': 'L-marker entry', 'url': '/v2.0.0/position_types/14'},
    {'id': 15, 'name': 'Emergency position', 'url': '/v2.0.0/position_types/15'},
    {'id': 16, 'name': 'Precision marker', 'url': '/v2.0.0/position_types/16'},
    {'id': 17, 'name': 'Precision marker entry', 'url': '/v2.0.0/position_types/17'},
    {'id': 18, 'name': 'Pallet rack', 'url': '/v2.0.0/position_types/18'},
    {'id': 19, 'name': 'Pallet rack entry position', 'url': '/v2.0.0/position_types/19'},
    {'id': 20, 'name': 'MiRCharge 500/1000', 'url': '/v2.0.0/position_types/20'},
    {'id': 21, 'name': 'MiRCharge 500/1000 entry', 'url': '/v2.0.0/position_types/21'},
    {'id': 22, 'name': 'Bar-marker', 'url': '/v2.0.0/position_types/22'},
    {'id': 23, 'name': 'Bar-marker entry', 'url': '/v2.0.0/position_types/23'},
    {'id': 25, 'name': 'elevator position', 'url': '/v2.0.0/position_types/25'},
    {'id': 26, 'name': 'elevator entry position', 'url': '/v2.0.0/position_types/26'},
    {'id': 42, 'name': 'Staging position', 'url': '/v2.0.0/position_types/42'},
    {'id': 106, 'name': 'Shelf long entry position', 'url': '/v2.0.0/position_types/106'}]]
    """

    self.method = "GET"
    self.endpoint = self.url + "/position_types/" + id
    self.json = ""

    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

positions_guid_get(guid, ros=0)

Retrieve the details about the position with the specified GUID

Parameters:

Name Type Description Default
guid str

The global id unique across robots that identifies this position

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int,dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
def positions_guid_get(self, guid: str, ros: bool = 0) -> [int,dict]:
    """Retrieve the details about the position with the specified GUID

    :param guid: The global id unique across robots that identifies this position
    :type guid: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int,dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/positions/" + guid
    self.json = ""

    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

positions_pos_id_docking_offsets_get(pos_id, ros=0)

Retrieve the details of the docking offset of the position with the specified position ID

Parameters:

Name Type Description Default
pos_id str

position ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int,dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
def positions_pos_id_docking_offsets_get(self, pos_id: str, ros: bool = 0) -> [int,dict]:
    """Retrieve the details of the docking offset of the position with the specified position ID

    :param pos_id: position ID
    :type pos_id: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int,dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/positions/" + pos_id + "/docking_offsets"
    self.json = ""

    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

positions_post(position, ros=0)

Add a new position.

Position json needs to have at least: {name, pos_x, pos_y, orientation, type_id, map_id}

Parameters:

Name Type Description Default
position json

position json

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
def positions_post(self, position, ros: bool = 0) -> [int, dict]: 
    """Add a new position.

    Position json needs to have at least: {name, pos_x, pos_y, orientation, type_id, map_id}

    :param position: position json
    :type position: json
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int, dict]
    """

    self.method = "POST"
    self.endpoint = self.url + "/positions"
    self.json = position
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

sessions_session_id_maps_get(session_id, ros=0)

Retrieve the list of maps that belong to the session with the specified session ID. session_id = site_id

Parameters:

Name Type Description Default
session_id str

site ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
def sessions_session_id_maps_get(self, session_id: str, ros: bool = 0) -> [int, dict]:
    """Retrieve the list of maps that belong to the session with the specified session ID. session_id = site_id

    :param session_id: site ID
    :type session_id: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/sessions/" + session_id + "/maps"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

setting_name_get(group_name, setting_name, ros=0)

Retrieve the details of the setting with the specified settings group name and setting name

Parameters:

Name Type Description Default
group_name str

settings group name

required
setting_name str

setting name

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int,dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
def setting_name_get(self, group_name: str, setting_name: str, ros: bool = 0) -> [int,dict]:
    """Retrieve the details of the setting with the specified settings group name and setting name

    :param group_name: settings group name
    :type group_name: str
    :param setting_name: setting name
    :type setting_name: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int,dict]
    """

    settings_list = self.settings_groups_name_get(group_name,ros)
    setting = next(item for item in settings_list[1] if item["name"] == setting_name)
    return [settings_list[0], setting]

settings_groups_get(ros=0)

Retrieve a list with the settings groups

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int, List[dict]]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
def settings_groups_get(self, ros: bool = 0) -> [int, List[dict]]:
    """Retrieve a list with the settings groups

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int, List[dict]]
    """

    self.method = "GET"
    self.endpoint = self.url + "/setting_groups"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

settings_groups_id_get(group_id, ros=0)

Retrieve the list of settings from the settings group with the specified settings group ID

Parameters:

Name Type Description Default
group_id int

settings group ID

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int, List[dict]]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
def settings_groups_id_get(self, group_id: int, ros: bool = 0) -> [int, List[dict]]:
    """Retrieve the list of settings from the settings group with the specified settings group ID

    :param group_id: settings group ID
    :type group_id: int
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int, List[dict]]
    """

    self.method = "GET"
    self.endpoint = self.url + "/setting_groups/" + str(group_id) + "/settings"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

settings_groups_name_get(group_name, ros=0)

Retrieve the list of settings from the settings group with the specified settings group name

Parameters:

Name Type Description Default
group_name str

settings group name

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
[int, List[dict]]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
def settings_groups_name_get(self, group_name: str, ros: bool = 0) -> [int, List[dict]]:
    """Retrieve the list of settings from the settings group with the specified settings group name

    :param group_name: settings group name
    :type group_name: str
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: [int, List[dict]]
    """

    groups = self.settings_groups_get(ros)
    setting_group = next(item for item in groups[1] if item["name"] == group_name)
    setting_group = self.settings_groups_id_get(setting_group["id"],ros)
    return setting_group

status_get(ros=0)

Retrieve the robot status

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
def status_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the robot status

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/status"
    self.json = ""
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

status_mode_get(ros=0)

Retrieve the current mode of the robot

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
def status_mode_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the current mode of the robot

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/status"
    self.json = ""
    if ros == 1:
        response =  self.handle_request_ros()
        return [response[0], {"mode_id": response[1]["mode_id"],"mode_text": response[1]["mode_text"], "mode_key_state":response[1]["mode_key_state"]}]
    else:
        response =  self.handle_request()
        return [response[0], {"mode_id": response[1]["mode_id"],"mode_text": response[1]["mode_text"], "mode_key_state":response[1]["mode_key_state"]}]

status_put(json, ros=0)

Modify the robot status

Parameters:

Name Type Description Default
json dict

request body

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
def status_put(self, json: dict, ros: bool = 0) -> [int, dict]:
    """Modify the robot status

    :param json: request body
    :type json: dict
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "PUT"
    self.endpoint = self.url + "/status"
    self.json = json
    if ros == 1:
        return self.handle_request_ros()
    else:
        return self.handle_request()

status_state_get(ros=0)

Retrieve the current state of the robot

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
def status_state_get(self, ros: bool = 0) -> [int, dict]:
    """Retrieve the current state of the robot

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    self.method = "GET"
    self.endpoint = self.url + "/status"
    self.json = ""
    if ros == 1:
        response =  self.handle_request_ros()
        return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]
    else:
        response =  self.handle_request()
        return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]

status_state_id_put(state_id, ros=0)

Modify the current state of the robot.

Possible robot state_id: {3, 4, 5, 11}, State: {Ready, Pause, Executing,Manual control}. Using this method the user can only put state_id: {3, 4}, State: {Ready, Pause}.

Parameters:

Name Type Description Default
state_id int

desired robot state

required
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
def status_state_id_put(self, state_id: int, ros: bool = 0) -> [int, dict]:
    """Modify the current state of the robot. 

    Possible robot state_id: {3, 4, 5, 11}, State: {Ready, Pause, Executing,Manual control}.
    Using this method the user can only put state_id: {3, 4}, State: {Ready, Pause}.

    :param state_id: desired robot state
    :type state_id: int
    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    if state_id !=3 and state_id != 4:
        print("INVALID INPUT. Select state_id=3 for 'Ready' or state_id=4 for 'Pause'")
        return

    self.method = "PUT"
    self.endpoint = self.url + "/status"
    self.json = {"state_id" : state_id}
    if ros == 1:
        response =  self.handle_request_ros()
        return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]
    else:
        response =  self.handle_request()
        return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]

status_state_id_toggle_put(ros=0)

Toggle the current state of the robot between 'Ready'/'Executing' and 'Pause'.

Parameters:

Name Type Description Default
ros bool

use ROS service, defaults to 0

0

Returns:

Type Description
list[int, dict]

a list containing REST response status code and body

Source code in docs/MiR100/mir_rest_api/api.py
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
def status_state_id_toggle_put(self, ros: bool = 0) -> [int, dict]:
    """Toggle the current state of the robot between 'Ready'/'Executing' and 'Pause'.

    :param ros: use ROS service, defaults to 0
    :type ros: bool, optional
    :return: a list containing REST response status code and body
    :rtype: list[int, dict]
    """

    status = self.status_state_get(ros)[1]
    if status["state_id"] == 3:
        state_id = 4
        # rospy.loginfo("Setting the robot state to: 'Pause'")
        print("Robot is in state: 'Ready'. Setting the robot state to: 'Pause'")
    elif status["state_id"] == 4:
        state_id = 3
        # rospy.loginfo("Setting the robot state to: 'Ready'")
        print("Robot is in state: 'Pause'. Setting the robot state to: 'Ready'/'Executing'")
    elif status ["state_id"] == 5:
        state_id = 4
        # rospy.loginfo("Setting the robot state to: 'Ready'")
        print("Robot is in state: 'Executing'. Setting the robot state to: 'Pause'")
    elif status ["state_id"] == 10:
        # rospy.loginfo("Setting the robot state to: 'Ready'")
        print("Robot is in state: 'EmergencyStop'. Unable to toggle robot status")
        return
    else:
        # rospy.logerr("Unable to toggle robot status")
        print("Unable to toggle robot status")
        return

    self.method = "PUT"
    self.endpoint = self.url + "/status"
    self.json = {"state_id" : state_id}
    if ros == 1:
        response =  self.handle_request_ros()
        return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]
    else:
        response =  self.handle_request()
        return [response[0], {"state_id": response[1]["state_id"],"state_text": response[1]["state_text"]}]