From 1d8c0f9575632bac29c58cdbc60de6177eab0981 Mon Sep 17 00:00:00 2001 From: Ben Schattinger Date: Mon, 6 Jul 2020 21:01:59 -0400 Subject: [PATCH] =?UTF-8?q?=F0=9F=A4=96=20Merge=20PR=20#45749=20[roslib]?= =?UTF-8?q?=20Add=20URDF=20classes=20by=20@lights0123?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Format to latest style guide * [roslib] Add URDF classes * Bump version and make typescript-bot rerun performance tests --- types/roslib/index.d.ts | 407 ++++++++++++++++++++++++++--------- types/roslib/roslib-tests.ts | 147 +++++++++++-- 2 files changed, 427 insertions(+), 127 deletions(-) diff --git a/types/roslib/index.d.ts b/types/roslib/index.d.ts index c83f35c47d..bca1c5b10f 100644 --- a/types/roslib/index.d.ts +++ b/types/roslib/index.d.ts @@ -1,12 +1,11 @@ -// Type definitions for roslib.js 1.0.1 +// Type definitions for roslib.js 1.1.0 // Project: http://wiki.ros.org/roslibjs // Definitions by: Stefan Profanter , // Cooper Benson , // David Gonzalez // Arvid Norlander // Definitions: https://github.com/DefinitelyTyped/DefinitelyTyped -// TypeScript Version: 3.0 - +// TypeScript Version: 3.7 /* ---------------------------------- @@ -18,6 +17,17 @@ export = ROSLIB; export as namespace ROSLIB; declare namespace ROSLIB { + interface Vector3Like { + x?: number | null; + y?: number | null; + z?: number | null; + } + interface QuaternionLike { + x?: number | null; + y?: number | null; + z?: number | null; + w?: number | null; + } export class Ros { /** * Manages connection to the server and all interactions with ROS. @@ -36,26 +46,26 @@ declare namespace ROSLIB { * * transportLibrary (optional) - one of 'websocket' (default), 'socket.io' or RTCPeerConnection instance controlling how the connection is created in `connect`. * * transportOptions (optional) - the options to use use when creating a connection. Currently only used if `transportLibrary` is RTCPeerConnection. */ - constructor(options:{ - url?: string, - groovyCompatibility?: boolean, - transportLibrary?: 'websocket' | 'socket.io' | RTCPeerConnection, - transportOptions?: RTCDataChannelInit + constructor(options: { + url?: string; + groovyCompatibility?: boolean; + transportLibrary?: 'websocket' | 'socket.io' | RTCPeerConnection; + transportOptions?: RTCDataChannelInit; }); - on(eventName:string, callback:(event:any) => void):void; + on(eventName: string, callback: (event: any) => void): void; /** * Connect to the specified WebSocket. * * @param url - WebSocket URL for Rosbridge */ - connect(url:string):void; + connect(url: string): void; /** * Disconnect from the WebSocket server. */ - close():void; + close(): void; /** * Sends an authorization request to the server. @@ -68,14 +78,21 @@ declare namespace ROSLIB { * @param level - User level as a string given by the client. * @param end - End time of the client's session. */ - authenticate(mac:string, client:string, dest:string, rand:string, t:number, level:string, end:number):void; - + authenticate( + mac: string, + client: string, + dest: string, + rand: string, + t: number, + level: string, + end: number, + ): void; /** * Sends the message over the WebSocket, but queues the message up if not yet * connected. */ - callOnConnection(message:any):void; + callOnConnection(message: any): void; /** * Retrieves list of actionlib servers in ROS as an array. @@ -85,7 +102,7 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getActionServers(callback:(action_servers:string[]) => void, failedCallback?:(error:any)=>void):void; + getActionServers(callback: (action_servers: string[]) => void, failedCallback?: (error: any) => void): void; /** * Retrieves list of topics in ROS as an array. @@ -95,7 +112,7 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getTopics(callback:(topics:string[]) => void, failedCallback?:(error:any)=>void):void; + getTopics(callback: (topics: string[]) => void, failedCallback?: (error: any) => void): void; /** * Retrieves Topics in ROS as an array as specific type @@ -106,7 +123,11 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getTopicsForType(topicType:string, callback:(topics:string[]) => void, failedCallback?:(error:any)=>void):void; + getTopicsForType( + topicType: string, + callback: (topics: string[]) => void, + failedCallback?: (error: any) => void, + ): void; /** * Retrieves list of active service names in ROS. @@ -116,7 +137,7 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getServices(callback:(services:string[]) => void, failedCallback?:(error:any)=>void):void; + getServices(callback: (services: string[]) => void, failedCallback?: (error: any) => void): void; /** * Retrieves list of services in ROS as an array as specific type @@ -127,7 +148,11 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getServicesForType(serviceType:string, callback:(services:string[]) => void, failedCallback?:(error:any)=>void):void; + getServicesForType( + serviceType: string, + callback: (services: string[]) => void, + failedCallback?: (error: any) => void, + ): void; /** * Retrieves list of active node names in ROS. @@ -137,7 +162,7 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getNodes(callback:(nodes:string[]) => void, failedCallback?:(error:any)=>void):void; + getNodes(callback: (nodes: string[]) => void, failedCallback?: (error: any) => void): void; /** * Retrieves list of param names from the ROS Parameter Server. @@ -147,7 +172,7 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getParams(callback:(params:string[]) => void, failedCallback?:(error:any)=>void):void; + getParams(callback: (params: string[]) => void, failedCallback?: (error: any) => void): void; /** * Retrieves a type of ROS topic. @@ -158,7 +183,7 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getTopicType(topic:string, callback:(type:string) => void, failedCallback?:(error:any)=>void):void; + getTopicType(topic: string, callback: (type: string) => void, failedCallback?: (error: any) => void): void; /** * Retrieves a type of ROS service. @@ -169,7 +194,7 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getServiceType(service:string, callback:(type:string) => void, failedCallback?:(error:any)=>void):void; + getServiceType(service: string, callback: (type: string) => void, failedCallback?: (error: any) => void): void; /** * Retrieves a detail of ROS message. @@ -180,14 +205,18 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the ros call failed (optional). Params: * * error - the error message reported by ROS */ - getMessageDetails(message:Message, callback:(detail:any) => void, failedCallback?:(error:any)=>void):void; + getMessageDetails( + message: Message, + callback: (detail: any) => void, + failedCallback?: (error: any) => void, + ): void; /** * Decode a typedefs into a dictionary like `rosmsg show foo/bar` * * @param defs - array of type_def dictionary */ - decodeTypeDefs(defs:any):void; + decodeTypeDefs(defs: any): void; } export class Message { @@ -197,7 +226,7 @@ declare namespace ROSLIB { * @constructor * @param values - object matching the fields defined in the .msg definition file */ - constructor(values:any); + constructor(values: any); } export class Param { @@ -209,10 +238,7 @@ declare namespace ROSLIB { * * ros - the ROSLIB.Ros connection handle * * name - the param name, like max_vel_x */ - constructor(options:{ - ros: Ros, - name: string - }); + constructor(options: { ros: Ros; name: string }); /** * Fetches the value of the param. @@ -220,7 +246,7 @@ declare namespace ROSLIB { * @param callback - function with the following params: * * value - the value of the param from ROS. */ - get(callback:(response:any) => void):void; + get(callback: (response: any) => void): void; /** * Sets the value of the param in ROS. @@ -229,16 +255,14 @@ declare namespace ROSLIB { * @param callback - function with params: * * response - the response from the service request */ - set(value:any, callback?:(response:any) => void):void; + set(value: any, callback?: (response: any) => void): void; /** * Delete this parameter on the ROS server. */ - delete(callback:(response:any) => void):void; - + delete(callback: (response: any) => void): void; } - export class Service { /** * A ROS service client. @@ -249,17 +273,12 @@ declare namespace ROSLIB { * * name - the service name, like /add_two_ints * * serviceType - the service type, like 'rospy_tutorials/AddTwoInts' */ - constructor(data:{ - ros: Ros, - name: string, - serviceType: string - }); - + constructor(data: { ros: Ros; name: string; serviceType: string }); // getter - public name:string; + public name: string; // getter - public serviceType:string; + public serviceType: string; /** * Calls the service. Returns the service response in the callback. @@ -270,7 +289,11 @@ declare namespace ROSLIB { * @param failedCallback - the callback function when the service call failed (optional). Params: * * error - the error message reported by ROS */ - callService(request:ServiceRequest, callback:(response:any) => void, failedCallback?:(error:any) => void):void; + callService( + request: ServiceRequest, + callback: (response: any) => void, + failedCallback?: (error: any) => void, + ): void; /** * Advertise this service and call the callback each time a client calls it. @@ -279,12 +302,12 @@ declare namespace ROSLIB { * * request - the service request data * * response - the data which should be sent back to the caller */ - advertise(callback:(request:any, response:any) => void):void; + advertise(callback: (request: any, response: any) => void): void; /** * Unadvertise a previously advertised service */ - unadvertise():void; + unadvertise(): void; } export class ServiceRequest { @@ -294,7 +317,7 @@ declare namespace ROSLIB { * @constructor * @param values - object matching the fields defined in the .srv definition file */ - constructor(values?:any); + constructor(values?: any); } export class ServiceResponse { @@ -304,7 +327,7 @@ declare namespace ROSLIB { * @constructor * @param values - object matching the fields defined in the .srv definition file */ - constructor(values?:any); + constructor(values?: any); } export class Topic { @@ -326,21 +349,21 @@ declare namespace ROSLIB { * * latch - latch the topic when publishing * * queue_length - the queue length at bridge side used when subscribing (defaults to 0, no queueing). */ - constructor(options:{ - ros: Ros, - name: string, - messageType: string, - compression?: string, - throttle_rate?: number, - queue_size?: number, - latch?: boolean, - queue_length?: number + constructor(options: { + ros: Ros; + name: string; + messageType: string; + compression?: string; + throttle_rate?: number; + queue_size?: number; + latch?: boolean; + queue_length?: number; }); // getter - public name:string; + public name: string; // getter - public messageType:string; + public messageType: string; /** * Every time a message is published for the given topic, the callback @@ -349,7 +372,7 @@ declare namespace ROSLIB { * @param callback - function with the following params: * * message - the published message */ - subscribe(callback:(message:Message) => void):void; + subscribe(callback: (message: Message) => void): void; /** * Unregisters as a subscriber for the topic. Unsubscribing stop remove @@ -360,24 +383,24 @@ declare namespace ROSLIB { * * provided and other listeners are registered the topic won't * * unsubscribe, just stop emitting to the passed listener */ - unsubscribe(callback?:(callback:(message:Message) => void) => void):void; + unsubscribe(callback?: (callback: (message: Message) => void) => void): void; /** * Registers as a publisher for the topic. */ - advertise():void; + advertise(): void; /** * Unregisters as a publisher for the topic. */ - unadvertise():void; + unadvertise(): void; /** * Publish the message. * * @param message - A ROSLIB.Message object. */ - publish(message:Message):void; + publish(message: Message): void; } export class TFClient { @@ -397,15 +420,15 @@ declare namespace ROSLIB { * * repubServiceName (optional) - the name of the republish_tfs service (non groovy compatibility mode only) default: '/republish_tfs' */ constructor(options: { - ros: Ros, + ros: Ros; fixedFrame?: string; - angularThres?: number, - transThres?: number, - rate?: number, - updateDelay?: number, - topicTimeout?: number, - serverName?: string, - repubServiceName?: string + angularThres?: number; + transThres?: number; + rate?: number; + updateDelay?: number; + topicTimeout?: number; + serverName?: string; + repubServiceName?: string; }); /** @@ -432,7 +455,7 @@ declare namespace ROSLIB { * @param callback - function with params: * * transform - the transform data */ - subscribe(frameId: string, callback:(transform:Transform) => void): void; + subscribe(frameId: string, callback: (transform: Transform) => void): void; /** * Unsubscribe from the given TF frame. @@ -440,7 +463,7 @@ declare namespace ROSLIB { * @param frameId - the TF frame to unsubscribe from * @param callback - the callback function to remove */ - unsubscribe(frameId: string, callback?:(transform:Transform) => void): void; + unsubscribe(frameId: string, callback?: (transform: Transform) => void): void; /** * Create and send a new goal (or service request) to the tf2_web_republisher based on the current list of TFs. @@ -457,10 +480,7 @@ declare namespace ROSLIB { * * translation - the Vector3 describing the translation * * rotation - the ROSLIB.Quaternion describing the rotation */ - constructor(options: { - translation: Vector3, - rotation: Quaternion - }); + constructor(options?: { translation?: Vector3Like | null; rotation?: QuaternionLike | null }); // getters public translation: Vector3; @@ -472,7 +492,7 @@ declare namespace ROSLIB { clone(): Transform; } - export class Vector3 { + export class Vector3 implements Vector3Like { /** * A 3D vector. * @@ -482,11 +502,7 @@ declare namespace ROSLIB { * * y - the y value * * z - the z value */ - constructor(options: { - x: number, - y: number, - z: number - }); + constructor(options?: { x?: number | null; y?: number | null; z?: number | null } | null); // getters public x: number; @@ -519,7 +535,7 @@ declare namespace ROSLIB { subtract(v: Vector3): void; } - export class Quaternion { + export class Quaternion implements QuaternionLike { /** * A Quaternion. * @@ -530,12 +546,7 @@ declare namespace ROSLIB { * * z - the z value * * w - the w value */ - constructor(options?: { - x: number, - y: number, - z: number, - w: number - }); + constructor(options?: { x?: number | null; y?: number | null; z?: number | null; w?: number | null } | null); // getters public x: number; @@ -575,6 +586,40 @@ declare namespace ROSLIB { normalize(): void; } + export class Pose { + position: Vector3; + orientation: Quaternion; + + /** + * A Pose in 3D space. Values are copied into this object. + * + * @constructor + * @param options - object with following keys: + * * position - the Vector3 describing the position + * * orientation - the ROSLIB.Quaternion describing the orientation + */ + constructor( + options?: { + position?: Vector3Like | null; + orientation?: QuaternionLike | null; + } | null, + ); + + /** + * Apply a transform against this pose. + * + * @param tf the transform + */ + applyTransform(tf: Transform): void; + + /** + * Clone a copy of this pose. + * + * @returns the cloned pose + */ + clone(): Pose; + } + class ActionClient { /** * An actionlib action client. @@ -592,17 +637,12 @@ declare namespace ROSLIB { * * actionName - the action message name, like 'actionlib_tutorials/FibonacciAction' * * timeout - the timeout length when connecting to the action server */ - constructor(options:{ - ros: Ros, - serverName: string, - actionName: string, - timeout: number - }); + constructor(options: { ros: Ros; serverName: string; actionName: string; timeout: number }); /** * Cancel all goals associated with this ActionClient. */ - cancel():void; + cancel(): void; } class Goal { @@ -617,10 +657,7 @@ declare namespace ROSLIB { * * actionClient - the ROSLIB.ActionClient to use with this goal * * goalMessage - The JSON object containing the goal for the action server */ - constructor(options:{ - actionClient: ActionClient, - goalMessage: any - }); + constructor(options: { actionClient: ActionClient; goalMessage: any }); /** * Connect callback functions to goal based events @@ -628,18 +665,178 @@ declare namespace ROSLIB { * @param eventName Name of event ('timeout', 'status', 'feedback', 'result') * @param callback Callback function executed on connected event */ - on(eventName:string, callback:(event:any) => void):void; + on(eventName: string, callback: (event: any) => void): void; /** * Send the goal to the action server. * * @param timeout (optional) - a timeout length for the goal's result */ - send(timeout?:number):void; + send(timeout?: number): void; /** * Cancel the current goal. */ - cancel():void; + cancel(): void; + } + + export class UrdfColor { + r: number; + g: number; + b: number; + a: number; + /** + * A Color element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export class UrdfMaterial { + textureFilename: string | null; + color: UrdfColor | null; + name: string; + + /** + * A Material element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + + isLink(): boolean; + } + + export class UrdfJoint { + name: string; + type: string; + parent: string | null; + child: string | null; + minval: number | null; + maxval: number | null; + + /** + * A Joint element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export const URDF_SPHERE: 0; + export const URDF_BOX: 1; + export const URDF_CYLINDER: 2; + export const URDF_MESH: 3; + + export type UrdfGeometry = UrdfSphere | UrdfBox | UrdfCylinder | UrdfMesh; + + export class UrdfSphere { + type: typeof URDF_SPHERE; + radius: number; + + /** + * A Sphere element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export class UrdfBox { + type: typeof URDF_BOX; + dimension: Vector3; + + /** + * A Box element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export class UrdfCylinder { + type: typeof URDF_CYLINDER; + length: number; + radius: number; + + /** + * A Cylinder element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export class UrdfMesh { + type: typeof URDF_MESH; + filename: string; + scale: Vector3 | null; + + /** + * A Box element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export class UrdfVisual { + origin: Pose | null; + geometry: UrdfGeometry | null; + material: UrdfMaterial | null; + + /** + * A Visual element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export class UrdfLink { + name: string; + visuals: UrdfVisual[]; + + /** + * A Link element in a URDF. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + */ + constructor(options: { xml: Node }); + } + + export class UrdfModel { + materials: Record; + links: Record; + joints: Record; + + /** + * A URDF Model can be used to parse a given URDF into the appropriate elements. + * + * @constructor + * @param options - object with following keys: + * * xml - the XML element to parse + * * string - the XML element to parse as a string + */ + constructor(options: { xml: Node; string?: string | null } | { string: string }); } } diff --git a/types/roslib/roslib-tests.ts b/types/roslib/roslib-tests.ts index ee404bf7e4..dbd410ac6b 100644 --- a/types/roslib/roslib-tests.ts +++ b/types/roslib/roslib-tests.ts @@ -1,7 +1,7 @@ -import ROSLIB = require("roslib"); +import ROSLIB = require('roslib'); var ros = new ROSLIB.Ros({ - url: 'ws://localhost:9090' + url: 'ws://localhost:9090', }); ros.on('connection', function () { @@ -22,20 +22,20 @@ ros.on('close', function () { var cmdVel = new ROSLIB.Topic({ ros: ros, name: '/cmd_vel', - messageType: 'geometry_msgs/Twist' + messageType: 'geometry_msgs/Twist', }); var twist = new ROSLIB.Message({ linear: { x: 0.1, y: 0.2, - z: 0.3 + z: 0.3, }, angular: { x: -0.1, y: -0.2, - z: -0.3 - } + z: -0.3, + }, }); cmdVel.publish(twist); @@ -45,13 +45,13 @@ cmdVel.publish(twist); var listener = new ROSLIB.Topic({ ros: ros, name: '/listener', - messageType: 'std_msgs/String' + messageType: 'std_msgs/String', }); -let subscription_callback = function (message:ROSLIB.Message) { +let subscription_callback = function (message: ROSLIB.Message) { console.log('Received message on ' + listener.name + ': ' + message); listener.unsubscribe(); -} +}; listener.subscribe(subscription_callback); listener.unsubscribe(subscription_callback); @@ -62,19 +62,16 @@ listener.unsubscribe(subscription_callback); var addTwoIntsClient = new ROSLIB.Service({ ros: ros, name: '/add_two_ints', - serviceType: 'rospy_tutorials/AddTwoInts' + serviceType: 'rospy_tutorials/AddTwoInts', }); var request = new ROSLIB.ServiceRequest({ a: 1, - b: 2 + b: 2, }); addTwoIntsClient.callService(request, function (result) { - console.log('Result for service call on ' - + addTwoIntsClient.name - + ': ' - + result.sum); + console.log('Result for service call on ' + addTwoIntsClient.name + ': ' + result.sum); }); // Providing a service @@ -83,24 +80,24 @@ addTwoIntsClient.callService(request, function (result) { var addTwoInts = new ROSLIB.Service({ ros: ros, name: '/add_two_ints', - serviceType: 'beginner_tutorials/AddTwoInts' + serviceType: 'beginner_tutorials/AddTwoInts', }); addTwoInts.advertise((req, resp) => { - resp.sum = req.a + req.b + resp.sum = req.a + req.b; return true; }); // Getting and setting a param value // --------------------------------- -ros.getParams(function (params:string[]) { +ros.getParams(function (params: string[]) { console.log(params); }); var maxVelX = new ROSLIB.Param({ ros: ros, - name: 'max_vel_y' + name: 'max_vel_y', }); maxVelX.set(0.8); @@ -112,12 +109,118 @@ maxVelX.get(function (value) { // -------------------- const tfClient = new ROSLIB.TFClient({ ros: ros, - fixedFrame: '/world' -}) + fixedFrame: '/world', +}); const tfclient_callback = function (transform: ROSLIB.Transform) { console.log('Received transform: ' + transform); tfClient.unsubscribe('/transform'); -} +}; tfClient.subscribe('/transform', tfclient_callback); tfClient.unsubscribe('/transform', tfclient_callback); + +new ROSLIB.Pose(); +new ROSLIB.Pose(null); +new ROSLIB.Pose({}); +new ROSLIB.Pose({ position: null }); +new ROSLIB.Pose({ orientation: null }); +new ROSLIB.Pose({ position: {} }); +new ROSLIB.Pose({ position: { x: 5 } }); +new ROSLIB.Pose({ position: { x: null } }); +new ROSLIB.Pose({ orientation: {} }); +new ROSLIB.Pose({ orientation: { y: -1 } }); +new ROSLIB.Pose({ orientation: { y: null } }); +const pose = new ROSLIB.Pose({ orientation: { w: 0, x: 0, y: 0, z: 0 }, position: { x: 0, y: 0, z: 0 } }); +// $ExpectType Pose +pose.clone(); +// $ExpectType Vector3 +pose.position; +// $ExpectType Quaternion +pose.orientation; + +// URDF +{ + const parser = new DOMParser(); + const document = parser.parseFromString('', 'text/xml'); + // $ExpectError + new ROSLIB.UrdfModel({}); + // $ExpectError + new ROSLIB.UrdfModel(); + new ROSLIB.UrdfModel({ xml: document }); + new ROSLIB.UrdfModel({ xml: document, string: '' }); + const model = new ROSLIB.UrdfModel({ string: '' }); + + const material: ROSLIB.UrdfMaterial = model.materials[0]; + + // $ExpectType string | null + material.textureFilename; + // $ExpectType UrdfColor | null + material.color; + // $ExpectType string + material.name; + // $ExpectType boolean + material.isLink(); + + if (material.color) { + // $ExpectType number + material.color.r; + // $ExpectType number + material.color.g; + // $ExpectType number + material.color.b; + // $ExpectType number + material.color.a; + } + + const link: ROSLIB.UrdfLink = model.links[0]; + // $ExpectType string + link.name; + + const visual: ROSLIB.UrdfVisual = link.visuals[0]; + // $ExpectType Pose | null + visual.origin; + // $ExpectType UrdfMaterial | null + visual.material; + switch (visual.geometry?.type) { + case ROSLIB.URDF_SPHERE: + // $ExpectType number + visual.geometry.radius; + // $ExpectError + visual.geometry.dimension; + break; + case ROSLIB.URDF_BOX: + // $ExpectType Vector3 + visual.geometry.dimension; + break; + case ROSLIB.URDF_CYLINDER: + // $ExpectType number + visual.geometry.length; + // $ExpectType number + visual.geometry.radius; + break; + case ROSLIB.URDF_MESH: + // $ExpectType string + visual.geometry.filename; + // $ExpectType Vector3 | null + visual.geometry.scale; + // $ExpectError + visual.geometry.length; + break; + } + // $ExpectError + visual.geometry?.radius; + + const joint: ROSLIB.UrdfJoint = model.joints[0]; + // $ExpectType string + joint.name; + // $ExpectType string + joint.type; + // $ExpectType string | null + joint.parent; + // $ExpectType string | null + joint.child; + // $ExpectType number | null + joint.minval; + // $ExpectType number | null + joint.maxval; +}