UNPKG

@foxglove/ros1

Version:

Standalone TypeScript implementation of the ROS 1 (Robot Operating System) protocol with a pluggable transport layer

111 lines (105 loc) 3.46 kB
import type { XmlRpcValue } from "@foxglove/xmlrpc"; import type { RosXmlRpcResponse } from "../XmlRpcTypes"; const TURTLESIM_SERVICES = new Set([ "/turtlesim/get_loggers", "/turtlesim/set_logger_level", "/clear", "/reset", "/spawn", "/kill", "/turtle1/set_pen", "/turtle1/teleport_relative", "/turtle1/teleport_absolute", "/rosout/get_loggers", "/rosout/set_logger_level", ]); export class XmlRpcClientMock { readonly serverUrl: string; constructor(serverUrl: string) { this.serverUrl = serverUrl; } async methodCall(method: string, args: XmlRpcValue[]): Promise<RosXmlRpcResponse> { switch (method) { case "getPublishedTopics": return [ 1, "current topics", [ ["/rosout", "rosgraph_msgs/Log"], ["/turtle1/pose", "turtlesim/Pose"], ["/turtle1/color_sensor", "turtlesim/Color"], ["/rosout_agg", "rosgraph_msgs/Log"], ], ]; case "getSystemState": return [ 1, "current system state", [ [ ["/rosout", ["/turtlesim"]], ["/turtle1/pose", ["/turtlesim"]], ["/turtle1/color_sensor", ["/turtlesim"]], ["/rosout_agg", ["/rosout"]], ], [ ["/turtle1/cmd_vel", ["/turtlesim"]], ["/rosout", ["/rosout"]], ], [ ["/turtlesim/get_loggers", ["/turtlesim"]], ["/turtlesim/set_logger_level", ["/turtlesim"]], ["/clear", ["/turtlesim"]], ["/reset", ["/turtlesim"]], ["/spawn", ["/turtlesim"]], ["/kill", ["/turtlesim"]], ["/turtle1/set_pen", ["/turtlesim"]], ["/turtle1/teleport_relative", ["/turtlesim"]], ["/turtle1/teleport_absolute", ["/turtlesim"]], ["/rosout/get_loggers", ["/rosout"]], ["/rosout/set_logger_level", ["/rosout"]], ], ], ]; case "getTopicTypes": return [ 1, "current system state", // Not a typo [ ["/rosout", "rosgraph_msgs/Log"], ["/turtle1/cmd_vel", "geometry_msgs/Twist"], ["/turtle1/pose", "turtlesim/Pose"], ["/turtle1/color_sensor", "turtlesim/Color"], ["/rosout_agg", "rosgraph_msgs/Log"], ], ]; case "getUri": return [1, "", "http://localhost:11311/"]; case "lookupNode": { const nodeName = args[1]; if (nodeName === "/turtlesim") { return [1, "node api", "http://localhost:39211/"]; } return [-1, `unknown node [${nodeName}]`, ""]; } case "lookupService": { const serviceName = args[1]; if (TURTLESIM_SERVICES.has(serviceName as string)) { return [1, "rosrpc URI: [rosrpc://localhost:38017]", "rosrpc://localhost:38017"]; } return [-1, "no provider", ""]; } case "registerPublisher": case "registerService": return [-1, "not implemented", ""]; case "registerSubscriber": return [1, "", ["http://localhost:39211/"]]; case "unregisterPublisher": case "unregisterService": case "unregisterSubscriber": return [-1, "not implemented", ""]; default: return [-1, `unknown method [${method}]`, ""]; } } }