@@ -29,6 +29,7 @@ export default class Ros extends EventEmitter {
29
29
idCounter = 0 ;
30
30
isConnected = false ;
31
31
groovyCompatibility = true ;
32
+ namespace = '' ;
32
33
/**
33
34
* @param {Object } [options]
34
35
* @param {string } [options.url] - The WebSocket URL for rosbridge. Can be specified later with `connect`.
@@ -180,7 +181,7 @@ export default class Ros extends EventEmitter {
180
181
/** @satisfies {Service<any, any> } */
181
182
var getActionServers = new Service ( {
182
183
ros : this ,
183
- name : 'rosapi/action_servers' ,
184
+ name : this . namespace + 'rosapi/action_servers' ,
184
185
serviceType : 'rosapi/GetActionServers'
185
186
} ) ;
186
187
@@ -220,7 +221,7 @@ export default class Ros extends EventEmitter {
220
221
getTopics ( callback , failedCallback ) {
221
222
var topicsClient = new Service ( {
222
223
ros : this ,
223
- name : 'rosapi/topics' ,
224
+ name : this . namespace + 'rosapi/topics' ,
224
225
serviceType : 'rosapi/Topics'
225
226
} ) ;
226
227
@@ -259,7 +260,7 @@ export default class Ros extends EventEmitter {
259
260
getTopicsForType ( topicType , callback , failedCallback ) {
260
261
var topicsForTypeClient = new Service ( {
261
262
ros : this ,
262
- name : 'rosapi/topics_for_type' ,
263
+ name : this . namespace + 'rosapi/topics_for_type' ,
263
264
serviceType : 'rosapi/TopicsForType'
264
265
} ) ;
265
266
@@ -299,7 +300,7 @@ export default class Ros extends EventEmitter {
299
300
getServices ( callback , failedCallback ) {
300
301
var servicesClient = new Service ( {
301
302
ros : this ,
302
- name : 'rosapi/services' ,
303
+ name : this . namespace + 'rosapi/services' ,
303
304
serviceType : 'rosapi/Services'
304
305
} ) ;
305
306
@@ -338,7 +339,7 @@ export default class Ros extends EventEmitter {
338
339
getServicesForType ( serviceType , callback , failedCallback ) {
339
340
var servicesForTypeClient = new Service ( {
340
341
ros : this ,
341
- name : 'rosapi/services_for_type' ,
342
+ name : this . namespace + 'rosapi/services_for_type' ,
342
343
serviceType : 'rosapi/ServicesForType'
343
344
} ) ;
344
345
@@ -380,7 +381,7 @@ export default class Ros extends EventEmitter {
380
381
getServiceRequestDetails ( type , callback , failedCallback ) {
381
382
var serviceTypeClient = new Service ( {
382
383
ros : this ,
383
- name : 'rosapi/service_request_details' ,
384
+ name : this . namespace + 'rosapi/service_request_details' ,
384
385
serviceType : 'rosapi/ServiceRequestDetails'
385
386
} ) ;
386
387
var request = {
@@ -422,7 +423,7 @@ export default class Ros extends EventEmitter {
422
423
/** @satisfies {Service<{},{typedefs: string[]}> } */
423
424
var serviceTypeClient = new Service ( {
424
425
ros : this ,
425
- name : 'rosapi/service_response_details' ,
426
+ name : this . namespace + 'rosapi/service_response_details' ,
426
427
serviceType : 'rosapi/ServiceResponseDetails'
427
428
} ) ;
428
429
var request = {
@@ -462,7 +463,7 @@ export default class Ros extends EventEmitter {
462
463
getNodes ( callback , failedCallback ) {
463
464
var nodesClient = new Service ( {
464
465
ros : this ,
465
- name : 'rosapi/nodes' ,
466
+ name : this . namespace + 'rosapi/nodes' ,
466
467
serviceType : 'rosapi/Nodes'
467
468
} ) ;
468
469
@@ -522,7 +523,7 @@ export default class Ros extends EventEmitter {
522
523
getNodeDetails ( node , callback , failedCallback ) {
523
524
var nodesClient = new Service ( {
524
525
ros : this ,
525
- name : 'rosapi/node_details' ,
526
+ name : this . namespace + 'rosapi/node_details' ,
526
527
serviceType : 'rosapi/NodeDetails'
527
528
} ) ;
528
529
@@ -563,7 +564,7 @@ export default class Ros extends EventEmitter {
563
564
getParams ( callback , failedCallback ) {
564
565
var paramsClient = new Service ( {
565
566
ros : this ,
566
- name : 'rosapi/get_param_names' ,
567
+ name : this . namespace + 'rosapi/get_param_names' ,
567
568
serviceType : 'rosapi/GetParamNames'
568
569
} ) ;
569
570
var request = { } ;
@@ -601,7 +602,7 @@ export default class Ros extends EventEmitter {
601
602
getTopicType ( topic , callback , failedCallback ) {
602
603
var topicTypeClient = new Service ( {
603
604
ros : this ,
604
- name : 'rosapi/topic_type' ,
605
+ name : this . namespace + 'rosapi/topic_type' ,
605
606
serviceType : 'rosapi/TopicType'
606
607
} ) ;
607
608
var request = {
@@ -642,7 +643,7 @@ export default class Ros extends EventEmitter {
642
643
getServiceType ( service , callback , failedCallback ) {
643
644
var serviceTypeClient = new Service ( {
644
645
ros : this ,
645
- name : 'rosapi/service_type' ,
646
+ name : this . namespace + 'rosapi/service_type' ,
646
647
serviceType : 'rosapi/ServiceType'
647
648
} ) ;
648
649
var request = {
@@ -683,7 +684,7 @@ export default class Ros extends EventEmitter {
683
684
getMessageDetails ( message , callback , failedCallback ) {
684
685
var messageDetailClient = new Service ( {
685
686
ros : this ,
686
- name : 'rosapi/message_details' ,
687
+ name : this . namespace + 'rosapi/message_details' ,
687
688
serviceType : 'rosapi/MessageDetails'
688
689
} ) ;
689
690
var request = {
@@ -775,7 +776,7 @@ export default class Ros extends EventEmitter {
775
776
getTopicsAndRawTypes ( callback , failedCallback ) {
776
777
var topicsAndRawTypesClient = new Service ( {
777
778
ros : this ,
778
- name : 'rosapi/topics_and_raw_types' ,
779
+ name : this . namespace + 'rosapi/topics_and_raw_types' ,
779
780
serviceType : 'rosapi/TopicsAndRawTypes'
780
781
} ) ;
781
782
0 commit comments