UNPKG

spot-sdk-ts

Version:

TypeScript bindings based on protobufs (proto3) provided by Boston Dynamics

979 lines 46.4 kB
"use strict"; var __importDefault = (this && this.__importDefault) || function (mod) { return (mod && mod.__esModule) ? mod : { "default": mod }; }; Object.defineProperty(exports, "__esModule", { value: true }); exports.BodyExternalForceParams = exports.TerrainParams = exports.ObstacleParams = exports.BodyControlParams_BodyAssistForManipulation = exports.BodyControlParams = exports.MobilityParams = exports.bodyExternalForceParams_ExternalForceIndicatorToJSON = exports.bodyExternalForceParams_ExternalForceIndicatorFromJSON = exports.BodyExternalForceParams_ExternalForceIndicator = exports.terrainParams_GratedSurfacesModeToJSON = exports.terrainParams_GratedSurfacesModeFromJSON = exports.TerrainParams_GratedSurfacesMode = exports.bodyControlParams_RotationSettingToJSON = exports.bodyControlParams_RotationSettingFromJSON = exports.BodyControlParams_RotationSetting = exports.swingHeightToJSON = exports.swingHeightFromJSON = exports.SwingHeight = exports.locomotionHintToJSON = exports.locomotionHintFromJSON = exports.LocomotionHint = exports.protobufPackage = void 0; /* eslint-disable */ const geometry_1 = require("../geometry"); const trajectory_1 = require("../trajectory"); const minimal_1 = __importDefault(require("protobufjs/minimal")); const wrappers_1 = require("../../../google/protobuf/wrappers"); exports.protobufPackage = "bosdyn.api.spot"; /** The locomotion hint specifying the gait of the robot. */ var LocomotionHint; (function (LocomotionHint) { /** HINT_UNKNOWN - Invalid; do not use. */ LocomotionHint[LocomotionHint["HINT_UNKNOWN"] = 0] = "HINT_UNKNOWN"; /** HINT_AUTO - No hint, robot chooses an appropriate gait (typically trot.) */ LocomotionHint[LocomotionHint["HINT_AUTO"] = 1] = "HINT_AUTO"; /** HINT_TROT - Most robust gait which moves diagonal legs together. */ LocomotionHint[LocomotionHint["HINT_TROT"] = 2] = "HINT_TROT"; /** HINT_SPEED_SELECT_TROT - Trot which comes to a stand when not commanded to move. */ LocomotionHint[LocomotionHint["HINT_SPEED_SELECT_TROT"] = 3] = "HINT_SPEED_SELECT_TROT"; /** HINT_CRAWL - Slow and steady gait which moves only one foot at a time. */ LocomotionHint[LocomotionHint["HINT_CRAWL"] = 4] = "HINT_CRAWL"; /** HINT_SPEED_SELECT_CRAWL - Crawl which comes to a stand when not commanded to move. */ LocomotionHint[LocomotionHint["HINT_SPEED_SELECT_CRAWL"] = 10] = "HINT_SPEED_SELECT_CRAWL"; /** HINT_AMBLE - Four beat gait where one foot touches down at a time. */ LocomotionHint[LocomotionHint["HINT_AMBLE"] = 5] = "HINT_AMBLE"; /** HINT_SPEED_SELECT_AMBLE - Amble which comes to a stand when not commanded to move. */ LocomotionHint[LocomotionHint["HINT_SPEED_SELECT_AMBLE"] = 6] = "HINT_SPEED_SELECT_AMBLE"; /** HINT_JOG - Demo gait which moves diagonal leg pairs together with an aerial phase. */ LocomotionHint[LocomotionHint["HINT_JOG"] = 7] = "HINT_JOG"; /** HINT_HOP - Demo gait which hops while holding some feet in the air. */ LocomotionHint[LocomotionHint["HINT_HOP"] = 8] = "HINT_HOP"; /** * HINT_AUTO_TROT - HINT_AUTO_TROT is deprecated due to the name being too similar to the Spot Autowalk feature. * It has been replaced by HINT_SPEED_SELECT_TROT. Keeping this value in here for now for backwards * compatibility, but this may be removed in future releases. */ LocomotionHint[LocomotionHint["HINT_AUTO_TROT"] = 3] = "HINT_AUTO_TROT"; /** * HINT_AUTO_AMBLE - HINT_AUTO_AMBLE is deprecated due to the name being too similar to the Spot Autowalk feature. * It has been replaced by HINT_SPEED_SELECT_AMBLE. Keeping this value in here for now for backwards * compatibility, but this may be removed in future releases. */ LocomotionHint[LocomotionHint["HINT_AUTO_AMBLE"] = 6] = "HINT_AUTO_AMBLE"; LocomotionHint[LocomotionHint["UNRECOGNIZED"] = -1] = "UNRECOGNIZED"; })(LocomotionHint = exports.LocomotionHint || (exports.LocomotionHint = {})); function locomotionHintFromJSON(object) { switch (object) { case 0: case "HINT_UNKNOWN": return LocomotionHint.HINT_UNKNOWN; case 1: case "HINT_AUTO": return LocomotionHint.HINT_AUTO; case 2: case "HINT_TROT": return LocomotionHint.HINT_TROT; case 3: case "HINT_SPEED_SELECT_TROT": return LocomotionHint.HINT_SPEED_SELECT_TROT; case 4: case "HINT_CRAWL": return LocomotionHint.HINT_CRAWL; case 10: case "HINT_SPEED_SELECT_CRAWL": return LocomotionHint.HINT_SPEED_SELECT_CRAWL; case 5: case "HINT_AMBLE": return LocomotionHint.HINT_AMBLE; case 6: case "HINT_SPEED_SELECT_AMBLE": return LocomotionHint.HINT_SPEED_SELECT_AMBLE; case 7: case "HINT_JOG": return LocomotionHint.HINT_JOG; case 8: case "HINT_HOP": return LocomotionHint.HINT_HOP; case 3: case "HINT_AUTO_TROT": return LocomotionHint.HINT_AUTO_TROT; case 6: case "HINT_AUTO_AMBLE": return LocomotionHint.HINT_AUTO_AMBLE; case -1: case "UNRECOGNIZED": default: return LocomotionHint.UNRECOGNIZED; } } exports.locomotionHintFromJSON = locomotionHintFromJSON; function locomotionHintToJSON(object) { switch (object) { case LocomotionHint.HINT_UNKNOWN: return "HINT_UNKNOWN"; case LocomotionHint.HINT_AUTO: return "HINT_AUTO"; case LocomotionHint.HINT_TROT: return "HINT_TROT"; case LocomotionHint.HINT_SPEED_SELECT_TROT: return "HINT_SPEED_SELECT_TROT"; case LocomotionHint.HINT_CRAWL: return "HINT_CRAWL"; case LocomotionHint.HINT_SPEED_SELECT_CRAWL: return "HINT_SPEED_SELECT_CRAWL"; case LocomotionHint.HINT_AMBLE: return "HINT_AMBLE"; case LocomotionHint.HINT_SPEED_SELECT_AMBLE: return "HINT_SPEED_SELECT_AMBLE"; case LocomotionHint.HINT_JOG: return "HINT_JOG"; case LocomotionHint.HINT_HOP: return "HINT_HOP"; case LocomotionHint.HINT_AUTO_TROT: return "HINT_AUTO_TROT"; case LocomotionHint.HINT_AUTO_AMBLE: return "HINT_AUTO_AMBLE"; case LocomotionHint.UNRECOGNIZED: default: return "UNRECOGNIZED"; } } exports.locomotionHintToJSON = locomotionHintToJSON; /** The type of swing height for a step. */ var SwingHeight; (function (SwingHeight) { /** SWING_HEIGHT_UNKNOWN - Invalid; do not use. */ SwingHeight[SwingHeight["SWING_HEIGHT_UNKNOWN"] = 0] = "SWING_HEIGHT_UNKNOWN"; /** SWING_HEIGHT_LOW - Low-stepping. Robot will try to only swing legs a few cm away from ground. */ SwingHeight[SwingHeight["SWING_HEIGHT_LOW"] = 1] = "SWING_HEIGHT_LOW"; /** SWING_HEIGHT_MEDIUM - Default for most cases, use other values with caution. */ SwingHeight[SwingHeight["SWING_HEIGHT_MEDIUM"] = 2] = "SWING_HEIGHT_MEDIUM"; /** SWING_HEIGHT_HIGH - High-stepping. Possibly useful with degraded vision operation. */ SwingHeight[SwingHeight["SWING_HEIGHT_HIGH"] = 3] = "SWING_HEIGHT_HIGH"; SwingHeight[SwingHeight["UNRECOGNIZED"] = -1] = "UNRECOGNIZED"; })(SwingHeight = exports.SwingHeight || (exports.SwingHeight = {})); function swingHeightFromJSON(object) { switch (object) { case 0: case "SWING_HEIGHT_UNKNOWN": return SwingHeight.SWING_HEIGHT_UNKNOWN; case 1: case "SWING_HEIGHT_LOW": return SwingHeight.SWING_HEIGHT_LOW; case 2: case "SWING_HEIGHT_MEDIUM": return SwingHeight.SWING_HEIGHT_MEDIUM; case 3: case "SWING_HEIGHT_HIGH": return SwingHeight.SWING_HEIGHT_HIGH; case -1: case "UNRECOGNIZED": default: return SwingHeight.UNRECOGNIZED; } } exports.swingHeightFromJSON = swingHeightFromJSON; function swingHeightToJSON(object) { switch (object) { case SwingHeight.SWING_HEIGHT_UNKNOWN: return "SWING_HEIGHT_UNKNOWN"; case SwingHeight.SWING_HEIGHT_LOW: return "SWING_HEIGHT_LOW"; case SwingHeight.SWING_HEIGHT_MEDIUM: return "SWING_HEIGHT_MEDIUM"; case SwingHeight.SWING_HEIGHT_HIGH: return "SWING_HEIGHT_HIGH"; case SwingHeight.UNRECOGNIZED: default: return "UNRECOGNIZED"; } } exports.swingHeightToJSON = swingHeightToJSON; /** * Setting for how the robot interprets base offset pitch & roll components. * In the default case (ROTATION_SETTING_OFFSET) the robot will naturally align the body to the pitch of the current terrain. * In some circumstances, the user may wish to override this value and try to maintain alignment * with respect to gravity. Be careful with this setting as it may likely degrade robot performance in * complex terrain, e.g. stairs, platforms, or slopes of sufficiently high grade. */ var BodyControlParams_RotationSetting; (function (BodyControlParams_RotationSetting) { /** ROTATION_SETTING_UNKNOWN - Invalid; do not use. */ BodyControlParams_RotationSetting[BodyControlParams_RotationSetting["ROTATION_SETTING_UNKNOWN"] = 0] = "ROTATION_SETTING_UNKNOWN"; /** ROTATION_SETTING_OFFSET - Pitch & Roll are offset with respect to orientation of the footprint. */ BodyControlParams_RotationSetting[BodyControlParams_RotationSetting["ROTATION_SETTING_OFFSET"] = 1] = "ROTATION_SETTING_OFFSET"; /** ROTATION_SETTING_ABSOLUTE - Pitch & Roll are offset with respect to gravity. */ BodyControlParams_RotationSetting[BodyControlParams_RotationSetting["ROTATION_SETTING_ABSOLUTE"] = 2] = "ROTATION_SETTING_ABSOLUTE"; BodyControlParams_RotationSetting[BodyControlParams_RotationSetting["UNRECOGNIZED"] = -1] = "UNRECOGNIZED"; })(BodyControlParams_RotationSetting = exports.BodyControlParams_RotationSetting || (exports.BodyControlParams_RotationSetting = {})); function bodyControlParams_RotationSettingFromJSON(object) { switch (object) { case 0: case "ROTATION_SETTING_UNKNOWN": return BodyControlParams_RotationSetting.ROTATION_SETTING_UNKNOWN; case 1: case "ROTATION_SETTING_OFFSET": return BodyControlParams_RotationSetting.ROTATION_SETTING_OFFSET; case 2: case "ROTATION_SETTING_ABSOLUTE": return BodyControlParams_RotationSetting.ROTATION_SETTING_ABSOLUTE; case -1: case "UNRECOGNIZED": default: return BodyControlParams_RotationSetting.UNRECOGNIZED; } } exports.bodyControlParams_RotationSettingFromJSON = bodyControlParams_RotationSettingFromJSON; function bodyControlParams_RotationSettingToJSON(object) { switch (object) { case BodyControlParams_RotationSetting.ROTATION_SETTING_UNKNOWN: return "ROTATION_SETTING_UNKNOWN"; case BodyControlParams_RotationSetting.ROTATION_SETTING_OFFSET: return "ROTATION_SETTING_OFFSET"; case BodyControlParams_RotationSetting.ROTATION_SETTING_ABSOLUTE: return "ROTATION_SETTING_ABSOLUTE"; case BodyControlParams_RotationSetting.UNRECOGNIZED: default: return "UNRECOGNIZED"; } } exports.bodyControlParams_RotationSettingToJSON = bodyControlParams_RotationSettingToJSON; /** * Options for Grated Surfaces Mode. When Grated Surfaces Mode is on, the robot assumes the * ground below it is made of grated metal or other repeated pattern. When on, the robot will * make assumptions about the environment structure and more aggressively filter noise in * perception data. */ var TerrainParams_GratedSurfacesMode; (function (TerrainParams_GratedSurfacesMode) { /** GRATED_SURFACES_MODE_UNKNOWN - Invalid; do not use. */ TerrainParams_GratedSurfacesMode[TerrainParams_GratedSurfacesMode["GRATED_SURFACES_MODE_UNKNOWN"] = 0] = "GRATED_SURFACES_MODE_UNKNOWN"; TerrainParams_GratedSurfacesMode[TerrainParams_GratedSurfacesMode["GRATED_SURFACES_MODE_OFF"] = 1] = "GRATED_SURFACES_MODE_OFF"; TerrainParams_GratedSurfacesMode[TerrainParams_GratedSurfacesMode["GRATED_SURFACES_MODE_ON"] = 2] = "GRATED_SURFACES_MODE_ON"; /** GRATED_SURFACES_MODE_AUTO - Robot will automatically turn mode on or off */ TerrainParams_GratedSurfacesMode[TerrainParams_GratedSurfacesMode["GRATED_SURFACES_MODE_AUTO"] = 3] = "GRATED_SURFACES_MODE_AUTO"; TerrainParams_GratedSurfacesMode[TerrainParams_GratedSurfacesMode["UNRECOGNIZED"] = -1] = "UNRECOGNIZED"; })(TerrainParams_GratedSurfacesMode = exports.TerrainParams_GratedSurfacesMode || (exports.TerrainParams_GratedSurfacesMode = {})); function terrainParams_GratedSurfacesModeFromJSON(object) { switch (object) { case 0: case "GRATED_SURFACES_MODE_UNKNOWN": return TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_UNKNOWN; case 1: case "GRATED_SURFACES_MODE_OFF": return TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_OFF; case 2: case "GRATED_SURFACES_MODE_ON": return TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_ON; case 3: case "GRATED_SURFACES_MODE_AUTO": return TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_AUTO; case -1: case "UNRECOGNIZED": default: return TerrainParams_GratedSurfacesMode.UNRECOGNIZED; } } exports.terrainParams_GratedSurfacesModeFromJSON = terrainParams_GratedSurfacesModeFromJSON; function terrainParams_GratedSurfacesModeToJSON(object) { switch (object) { case TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_UNKNOWN: return "GRATED_SURFACES_MODE_UNKNOWN"; case TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_OFF: return "GRATED_SURFACES_MODE_OFF"; case TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_ON: return "GRATED_SURFACES_MODE_ON"; case TerrainParams_GratedSurfacesMode.GRATED_SURFACES_MODE_AUTO: return "GRATED_SURFACES_MODE_AUTO"; case TerrainParams_GratedSurfacesMode.UNRECOGNIZED: default: return "UNRECOGNIZED"; } } exports.terrainParams_GratedSurfacesModeToJSON = terrainParams_GratedSurfacesModeToJSON; /** * Indicates what external force estimate/override the robot should use. * By default, the external force estimator is disabled on the robot. */ var BodyExternalForceParams_ExternalForceIndicator; (function (BodyExternalForceParams_ExternalForceIndicator) { /** EXTERNAL_FORCE_NONE - No external forces considered. */ BodyExternalForceParams_ExternalForceIndicator[BodyExternalForceParams_ExternalForceIndicator["EXTERNAL_FORCE_NONE"] = 0] = "EXTERNAL_FORCE_NONE"; /** EXTERNAL_FORCE_USE_ESTIMATE - Use external forces estimated by the robot */ BodyExternalForceParams_ExternalForceIndicator[BodyExternalForceParams_ExternalForceIndicator["EXTERNAL_FORCE_USE_ESTIMATE"] = 1] = "EXTERNAL_FORCE_USE_ESTIMATE"; /** EXTERNAL_FORCE_USE_OVERRIDE - Use external forces specified in an override vector. */ BodyExternalForceParams_ExternalForceIndicator[BodyExternalForceParams_ExternalForceIndicator["EXTERNAL_FORCE_USE_OVERRIDE"] = 2] = "EXTERNAL_FORCE_USE_OVERRIDE"; BodyExternalForceParams_ExternalForceIndicator[BodyExternalForceParams_ExternalForceIndicator["UNRECOGNIZED"] = -1] = "UNRECOGNIZED"; })(BodyExternalForceParams_ExternalForceIndicator = exports.BodyExternalForceParams_ExternalForceIndicator || (exports.BodyExternalForceParams_ExternalForceIndicator = {})); function bodyExternalForceParams_ExternalForceIndicatorFromJSON(object) { switch (object) { case 0: case "EXTERNAL_FORCE_NONE": return BodyExternalForceParams_ExternalForceIndicator.EXTERNAL_FORCE_NONE; case 1: case "EXTERNAL_FORCE_USE_ESTIMATE": return BodyExternalForceParams_ExternalForceIndicator.EXTERNAL_FORCE_USE_ESTIMATE; case 2: case "EXTERNAL_FORCE_USE_OVERRIDE": return BodyExternalForceParams_ExternalForceIndicator.EXTERNAL_FORCE_USE_OVERRIDE; case -1: case "UNRECOGNIZED": default: return BodyExternalForceParams_ExternalForceIndicator.UNRECOGNIZED; } } exports.bodyExternalForceParams_ExternalForceIndicatorFromJSON = bodyExternalForceParams_ExternalForceIndicatorFromJSON; function bodyExternalForceParams_ExternalForceIndicatorToJSON(object) { switch (object) { case BodyExternalForceParams_ExternalForceIndicator.EXTERNAL_FORCE_NONE: return "EXTERNAL_FORCE_NONE"; case BodyExternalForceParams_ExternalForceIndicator.EXTERNAL_FORCE_USE_ESTIMATE: return "EXTERNAL_FORCE_USE_ESTIMATE"; case BodyExternalForceParams_ExternalForceIndicator.EXTERNAL_FORCE_USE_OVERRIDE: return "EXTERNAL_FORCE_USE_OVERRIDE"; case BodyExternalForceParams_ExternalForceIndicator.UNRECOGNIZED: default: return "UNRECOGNIZED"; } } exports.bodyExternalForceParams_ExternalForceIndicatorToJSON = bodyExternalForceParams_ExternalForceIndicatorToJSON; function createBaseMobilityParams() { return { velLimit: undefined, bodyControl: undefined, locomotionHint: 0, stairHint: false, allowDegradedPerception: false, obstacleParams: undefined, swingHeight: 0, terrainParams: undefined, disallowStairTracker: false, disableStairErrorAutoDescent: false, externalForceParams: undefined, disallowNonStairsPitchLimiting: false, disableNearmapCliffAvoidance: false, }; } exports.MobilityParams = { encode(message, writer = minimal_1.default.Writer.create()) { if (message.velLimit !== undefined) { geometry_1.SE2VelocityLimit.encode(message.velLimit, writer.uint32(10).fork()).ldelim(); } if (message.bodyControl !== undefined) { exports.BodyControlParams.encode(message.bodyControl, writer.uint32(18).fork()).ldelim(); } if (message.locomotionHint !== 0) { writer.uint32(24).int32(message.locomotionHint); } if (message.stairHint === true) { writer.uint32(32).bool(message.stairHint); } if (message.allowDegradedPerception === true) { writer.uint32(40).bool(message.allowDegradedPerception); } if (message.obstacleParams !== undefined) { exports.ObstacleParams.encode(message.obstacleParams, writer.uint32(50).fork()).ldelim(); } if (message.swingHeight !== 0) { writer.uint32(56).int32(message.swingHeight); } if (message.terrainParams !== undefined) { exports.TerrainParams.encode(message.terrainParams, writer.uint32(66).fork()).ldelim(); } if (message.disallowStairTracker === true) { writer.uint32(72).bool(message.disallowStairTracker); } if (message.disableStairErrorAutoDescent === true) { writer.uint32(128).bool(message.disableStairErrorAutoDescent); } if (message.externalForceParams !== undefined) { exports.BodyExternalForceParams.encode(message.externalForceParams, writer.uint32(82).fork()).ldelim(); } if (message.disallowNonStairsPitchLimiting === true) { writer.uint32(88).bool(message.disallowNonStairsPitchLimiting); } if (message.disableNearmapCliffAvoidance === true) { writer.uint32(96).bool(message.disableNearmapCliffAvoidance); } return writer; }, decode(input, length) { const reader = input instanceof minimal_1.default.Reader ? input : new minimal_1.default.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseMobilityParams(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.velLimit = geometry_1.SE2VelocityLimit.decode(reader, reader.uint32()); break; case 2: message.bodyControl = exports.BodyControlParams.decode(reader, reader.uint32()); break; case 3: message.locomotionHint = reader.int32(); break; case 4: message.stairHint = reader.bool(); break; case 5: message.allowDegradedPerception = reader.bool(); break; case 6: message.obstacleParams = exports.ObstacleParams.decode(reader, reader.uint32()); break; case 7: message.swingHeight = reader.int32(); break; case 8: message.terrainParams = exports.TerrainParams.decode(reader, reader.uint32()); break; case 9: message.disallowStairTracker = reader.bool(); break; case 16: message.disableStairErrorAutoDescent = reader.bool(); break; case 10: message.externalForceParams = exports.BodyExternalForceParams.decode(reader, reader.uint32()); break; case 11: message.disallowNonStairsPitchLimiting = reader.bool(); break; case 12: message.disableNearmapCliffAvoidance = reader.bool(); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object) { return { velLimit: isSet(object.velLimit) ? geometry_1.SE2VelocityLimit.fromJSON(object.velLimit) : undefined, bodyControl: isSet(object.bodyControl) ? exports.BodyControlParams.fromJSON(object.bodyControl) : undefined, locomotionHint: isSet(object.locomotionHint) ? locomotionHintFromJSON(object.locomotionHint) : 0, stairHint: isSet(object.stairHint) ? Boolean(object.stairHint) : false, allowDegradedPerception: isSet(object.allowDegradedPerception) ? Boolean(object.allowDegradedPerception) : false, obstacleParams: isSet(object.obstacleParams) ? exports.ObstacleParams.fromJSON(object.obstacleParams) : undefined, swingHeight: isSet(object.swingHeight) ? swingHeightFromJSON(object.swingHeight) : 0, terrainParams: isSet(object.terrainParams) ? exports.TerrainParams.fromJSON(object.terrainParams) : undefined, disallowStairTracker: isSet(object.disallowStairTracker) ? Boolean(object.disallowStairTracker) : false, disableStairErrorAutoDescent: isSet(object.disableStairErrorAutoDescent) ? Boolean(object.disableStairErrorAutoDescent) : false, externalForceParams: isSet(object.externalForceParams) ? exports.BodyExternalForceParams.fromJSON(object.externalForceParams) : undefined, disallowNonStairsPitchLimiting: isSet(object.disallowNonStairsPitchLimiting) ? Boolean(object.disallowNonStairsPitchLimiting) : false, disableNearmapCliffAvoidance: isSet(object.disableNearmapCliffAvoidance) ? Boolean(object.disableNearmapCliffAvoidance) : false, }; }, toJSON(message) { const obj = {}; message.velLimit !== undefined && (obj.velLimit = message.velLimit ? geometry_1.SE2VelocityLimit.toJSON(message.velLimit) : undefined); message.bodyControl !== undefined && (obj.bodyControl = message.bodyControl ? exports.BodyControlParams.toJSON(message.bodyControl) : undefined); message.locomotionHint !== undefined && (obj.locomotionHint = locomotionHintToJSON(message.locomotionHint)); message.stairHint !== undefined && (obj.stairHint = message.stairHint); message.allowDegradedPerception !== undefined && (obj.allowDegradedPerception = message.allowDegradedPerception); message.obstacleParams !== undefined && (obj.obstacleParams = message.obstacleParams ? exports.ObstacleParams.toJSON(message.obstacleParams) : undefined); message.swingHeight !== undefined && (obj.swingHeight = swingHeightToJSON(message.swingHeight)); message.terrainParams !== undefined && (obj.terrainParams = message.terrainParams ? exports.TerrainParams.toJSON(message.terrainParams) : undefined); message.disallowStairTracker !== undefined && (obj.disallowStairTracker = message.disallowStairTracker); message.disableStairErrorAutoDescent !== undefined && (obj.disableStairErrorAutoDescent = message.disableStairErrorAutoDescent); message.externalForceParams !== undefined && (obj.externalForceParams = message.externalForceParams ? exports.BodyExternalForceParams.toJSON(message.externalForceParams) : undefined); message.disallowNonStairsPitchLimiting !== undefined && (obj.disallowNonStairsPitchLimiting = message.disallowNonStairsPitchLimiting); message.disableNearmapCliffAvoidance !== undefined && (obj.disableNearmapCliffAvoidance = message.disableNearmapCliffAvoidance); return obj; }, fromPartial(object) { const message = createBaseMobilityParams(); message.velLimit = object.velLimit !== undefined && object.velLimit !== null ? geometry_1.SE2VelocityLimit.fromPartial(object.velLimit) : undefined; message.bodyControl = object.bodyControl !== undefined && object.bodyControl !== null ? exports.BodyControlParams.fromPartial(object.bodyControl) : undefined; message.locomotionHint = object.locomotionHint ?? 0; message.stairHint = object.stairHint ?? false; message.allowDegradedPerception = object.allowDegradedPerception ?? false; message.obstacleParams = object.obstacleParams !== undefined && object.obstacleParams !== null ? exports.ObstacleParams.fromPartial(object.obstacleParams) : undefined; message.swingHeight = object.swingHeight ?? 0; message.terrainParams = object.terrainParams !== undefined && object.terrainParams !== null ? exports.TerrainParams.fromPartial(object.terrainParams) : undefined; message.disallowStairTracker = object.disallowStairTracker ?? false; message.disableStairErrorAutoDescent = object.disableStairErrorAutoDescent ?? false; message.externalForceParams = object.externalForceParams !== undefined && object.externalForceParams !== null ? exports.BodyExternalForceParams.fromPartial(object.externalForceParams) : undefined; message.disallowNonStairsPitchLimiting = object.disallowNonStairsPitchLimiting ?? false; message.disableNearmapCliffAvoidance = object.disableNearmapCliffAvoidance ?? false; return message; }, }; function createBaseBodyControlParams() { return { baseOffsetRtFootprint: undefined, bodyAssistForManipulation: undefined, rotationSetting: 0, }; } exports.BodyControlParams = { encode(message, writer = minimal_1.default.Writer.create()) { if (message.baseOffsetRtFootprint !== undefined) { trajectory_1.SE3Trajectory.encode(message.baseOffsetRtFootprint, writer.uint32(10).fork()).ldelim(); } if (message.bodyAssistForManipulation !== undefined) { exports.BodyControlParams_BodyAssistForManipulation.encode(message.bodyAssistForManipulation, writer.uint32(26).fork()).ldelim(); } if (message.rotationSetting !== 0) { writer.uint32(16).int32(message.rotationSetting); } return writer; }, decode(input, length) { const reader = input instanceof minimal_1.default.Reader ? input : new minimal_1.default.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseBodyControlParams(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.baseOffsetRtFootprint = trajectory_1.SE3Trajectory.decode(reader, reader.uint32()); break; case 3: message.bodyAssistForManipulation = exports.BodyControlParams_BodyAssistForManipulation.decode(reader, reader.uint32()); break; case 2: message.rotationSetting = reader.int32(); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object) { return { baseOffsetRtFootprint: isSet(object.baseOffsetRtFootprint) ? trajectory_1.SE3Trajectory.fromJSON(object.baseOffsetRtFootprint) : undefined, bodyAssistForManipulation: isSet(object.bodyAssistForManipulation) ? exports.BodyControlParams_BodyAssistForManipulation.fromJSON(object.bodyAssistForManipulation) : undefined, rotationSetting: isSet(object.rotationSetting) ? bodyControlParams_RotationSettingFromJSON(object.rotationSetting) : 0, }; }, toJSON(message) { const obj = {}; message.baseOffsetRtFootprint !== undefined && (obj.baseOffsetRtFootprint = message.baseOffsetRtFootprint ? trajectory_1.SE3Trajectory.toJSON(message.baseOffsetRtFootprint) : undefined); message.bodyAssistForManipulation !== undefined && (obj.bodyAssistForManipulation = message.bodyAssistForManipulation ? exports.BodyControlParams_BodyAssistForManipulation.toJSON(message.bodyAssistForManipulation) : undefined); message.rotationSetting !== undefined && (obj.rotationSetting = bodyControlParams_RotationSettingToJSON(message.rotationSetting)); return obj; }, fromPartial(object) { const message = createBaseBodyControlParams(); message.baseOffsetRtFootprint = object.baseOffsetRtFootprint !== undefined && object.baseOffsetRtFootprint !== null ? trajectory_1.SE3Trajectory.fromPartial(object.baseOffsetRtFootprint) : undefined; message.bodyAssistForManipulation = object.bodyAssistForManipulation !== undefined && object.bodyAssistForManipulation !== null ? exports.BodyControlParams_BodyAssistForManipulation.fromPartial(object.bodyAssistForManipulation) : undefined; message.rotationSetting = object.rotationSetting ?? 0; return message; }, }; function createBaseBodyControlParams_BodyAssistForManipulation() { return { enableBodyYawAssist: false, enableHipHeightAssist: false }; } exports.BodyControlParams_BodyAssistForManipulation = { encode(message, writer = minimal_1.default.Writer.create()) { if (message.enableBodyYawAssist === true) { writer.uint32(8).bool(message.enableBodyYawAssist); } if (message.enableHipHeightAssist === true) { writer.uint32(16).bool(message.enableHipHeightAssist); } return writer; }, decode(input, length) { const reader = input instanceof minimal_1.default.Reader ? input : new minimal_1.default.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseBodyControlParams_BodyAssistForManipulation(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.enableBodyYawAssist = reader.bool(); break; case 2: message.enableHipHeightAssist = reader.bool(); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object) { return { enableBodyYawAssist: isSet(object.enableBodyYawAssist) ? Boolean(object.enableBodyYawAssist) : false, enableHipHeightAssist: isSet(object.enableHipHeightAssist) ? Boolean(object.enableHipHeightAssist) : false, }; }, toJSON(message) { const obj = {}; message.enableBodyYawAssist !== undefined && (obj.enableBodyYawAssist = message.enableBodyYawAssist); message.enableHipHeightAssist !== undefined && (obj.enableHipHeightAssist = message.enableHipHeightAssist); return obj; }, fromPartial(object) { const message = createBaseBodyControlParams_BodyAssistForManipulation(); message.enableBodyYawAssist = object.enableBodyYawAssist ?? false; message.enableHipHeightAssist = object.enableHipHeightAssist ?? false; return message; }, }; function createBaseObstacleParams() { return { disableVisionFootObstacleAvoidance: false, disableVisionFootConstraintAvoidance: false, disableVisionBodyObstacleAvoidance: false, obstacleAvoidancePadding: 0, disableVisionFootObstacleBodyAssist: false, disableVisionNegativeObstacles: false, }; } exports.ObstacleParams = { encode(message, writer = minimal_1.default.Writer.create()) { if (message.disableVisionFootObstacleAvoidance === true) { writer.uint32(8).bool(message.disableVisionFootObstacleAvoidance); } if (message.disableVisionFootConstraintAvoidance === true) { writer.uint32(16).bool(message.disableVisionFootConstraintAvoidance); } if (message.disableVisionBodyObstacleAvoidance === true) { writer.uint32(24).bool(message.disableVisionBodyObstacleAvoidance); } if (message.obstacleAvoidancePadding !== 0) { writer.uint32(33).double(message.obstacleAvoidancePadding); } if (message.disableVisionFootObstacleBodyAssist === true) { writer.uint32(40).bool(message.disableVisionFootObstacleBodyAssist); } if (message.disableVisionNegativeObstacles === true) { writer.uint32(48).bool(message.disableVisionNegativeObstacles); } return writer; }, decode(input, length) { const reader = input instanceof minimal_1.default.Reader ? input : new minimal_1.default.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseObstacleParams(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.disableVisionFootObstacleAvoidance = reader.bool(); break; case 2: message.disableVisionFootConstraintAvoidance = reader.bool(); break; case 3: message.disableVisionBodyObstacleAvoidance = reader.bool(); break; case 4: message.obstacleAvoidancePadding = reader.double(); break; case 5: message.disableVisionFootObstacleBodyAssist = reader.bool(); break; case 6: message.disableVisionNegativeObstacles = reader.bool(); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object) { return { disableVisionFootObstacleAvoidance: isSet(object.disableVisionFootObstacleAvoidance) ? Boolean(object.disableVisionFootObstacleAvoidance) : false, disableVisionFootConstraintAvoidance: isSet(object.disableVisionFootConstraintAvoidance) ? Boolean(object.disableVisionFootConstraintAvoidance) : false, disableVisionBodyObstacleAvoidance: isSet(object.disableVisionBodyObstacleAvoidance) ? Boolean(object.disableVisionBodyObstacleAvoidance) : false, obstacleAvoidancePadding: isSet(object.obstacleAvoidancePadding) ? Number(object.obstacleAvoidancePadding) : 0, disableVisionFootObstacleBodyAssist: isSet(object.disableVisionFootObstacleBodyAssist) ? Boolean(object.disableVisionFootObstacleBodyAssist) : false, disableVisionNegativeObstacles: isSet(object.disableVisionNegativeObstacles) ? Boolean(object.disableVisionNegativeObstacles) : false, }; }, toJSON(message) { const obj = {}; message.disableVisionFootObstacleAvoidance !== undefined && (obj.disableVisionFootObstacleAvoidance = message.disableVisionFootObstacleAvoidance); message.disableVisionFootConstraintAvoidance !== undefined && (obj.disableVisionFootConstraintAvoidance = message.disableVisionFootConstraintAvoidance); message.disableVisionBodyObstacleAvoidance !== undefined && (obj.disableVisionBodyObstacleAvoidance = message.disableVisionBodyObstacleAvoidance); message.obstacleAvoidancePadding !== undefined && (obj.obstacleAvoidancePadding = message.obstacleAvoidancePadding); message.disableVisionFootObstacleBodyAssist !== undefined && (obj.disableVisionFootObstacleBodyAssist = message.disableVisionFootObstacleBodyAssist); message.disableVisionNegativeObstacles !== undefined && (obj.disableVisionNegativeObstacles = message.disableVisionNegativeObstacles); return obj; }, fromPartial(object) { const message = createBaseObstacleParams(); message.disableVisionFootObstacleAvoidance = object.disableVisionFootObstacleAvoidance ?? false; message.disableVisionFootConstraintAvoidance = object.disableVisionFootConstraintAvoidance ?? false; message.disableVisionBodyObstacleAvoidance = object.disableVisionBodyObstacleAvoidance ?? false; message.obstacleAvoidancePadding = object.obstacleAvoidancePadding ?? 0; message.disableVisionFootObstacleBodyAssist = object.disableVisionFootObstacleBodyAssist ?? false; message.disableVisionNegativeObstacles = object.disableVisionNegativeObstacles ?? false; return message; }, }; function createBaseTerrainParams() { return { groundMuHint: undefined, enableGratedFloor: false, gratedSurfacesMode: 0, }; } exports.TerrainParams = { encode(message, writer = minimal_1.default.Writer.create()) { if (message.groundMuHint !== undefined) { wrappers_1.DoubleValue.encode({ value: message.groundMuHint }, writer.uint32(18).fork()).ldelim(); } if (message.enableGratedFloor === true) { writer.uint32(24).bool(message.enableGratedFloor); } if (message.gratedSurfacesMode !== 0) { writer.uint32(32).int32(message.gratedSurfacesMode); } return writer; }, decode(input, length) { const reader = input instanceof minimal_1.default.Reader ? input : new minimal_1.default.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseTerrainParams(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 2: message.groundMuHint = wrappers_1.DoubleValue.decode(reader, reader.uint32()).value; break; case 3: message.enableGratedFloor = reader.bool(); break; case 4: message.gratedSurfacesMode = reader.int32(); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object) { return { groundMuHint: isSet(object.groundMuHint) ? Number(object.groundMuHint) : undefined, enableGratedFloor: isSet(object.enableGratedFloor) ? Boolean(object.enableGratedFloor) : false, gratedSurfacesMode: isSet(object.gratedSurfacesMode) ? terrainParams_GratedSurfacesModeFromJSON(object.gratedSurfacesMode) : 0, }; }, toJSON(message) { const obj = {}; message.groundMuHint !== undefined && (obj.groundMuHint = message.groundMuHint); message.enableGratedFloor !== undefined && (obj.enableGratedFloor = message.enableGratedFloor); message.gratedSurfacesMode !== undefined && (obj.gratedSurfacesMode = terrainParams_GratedSurfacesModeToJSON(message.gratedSurfacesMode)); return obj; }, fromPartial(object) { const message = createBaseTerrainParams(); message.groundMuHint = object.groundMuHint ?? undefined; message.enableGratedFloor = object.enableGratedFloor ?? false; message.gratedSurfacesMode = object.gratedSurfacesMode ?? 0; return message; }, }; function createBaseBodyExternalForceParams() { return { externalForceIndicator: 0, frameName: "", externalForceOverride: undefined, }; } exports.BodyExternalForceParams = { encode(message, writer = minimal_1.default.Writer.create()) { if (message.externalForceIndicator !== 0) { writer.uint32(8).int32(message.externalForceIndicator); } if (message.frameName !== "") { writer.uint32(34).string(message.frameName); } if (message.externalForceOverride !== undefined) { geometry_1.Vec3.encode(message.externalForceOverride, writer.uint32(26).fork()).ldelim(); } return writer; }, decode(input, length) { const reader = input instanceof minimal_1.default.Reader ? input : new minimal_1.default.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseBodyExternalForceParams(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.externalForceIndicator = reader.int32(); break; case 4: message.frameName = reader.string(); break; case 3: message.externalForceOverride = geometry_1.Vec3.decode(reader, reader.uint32()); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object) { return { externalForceIndicator: isSet(object.externalForceIndicator) ? bodyExternalForceParams_ExternalForceIndicatorFromJSON(object.externalForceIndicator) : 0, frameName: isSet(object.frameName) ? String(object.frameName) : "", externalForceOverride: isSet(object.externalForceOverride) ? geometry_1.Vec3.fromJSON(object.externalForceOverride) : undefined, }; }, toJSON(message) { const obj = {}; message.externalForceIndicator !== undefined && (obj.externalForceIndicator = bodyExternalForceParams_ExternalForceIndicatorToJSON(message.externalForceIndicator)); message.frameName !== undefined && (obj.frameName = message.frameName); message.externalForceOverride !== undefined && (obj.externalForceOverride = message.externalForceOverride ? geometry_1.Vec3.toJSON(message.externalForceOverride) : undefined); return obj; }, fromPartial(object) { const message = createBaseBodyExternalForceParams(); message.externalForceIndicator = object.externalForceIndicator ?? 0; message.frameName = object.frameName ?? ""; message.externalForceOverride = object.externalForceOverride !== undefined && object.externalForceOverride !== null ? geometry_1.Vec3.fromPartial(object.externalForceOverride) : undefined; return message; }, }; function isSet(value) { return value !== null && value !== undefined; } //# sourceMappingURL=robot_command.js.map