/* eslint-disable */ import { SoftwareVersion } from "./robot_id"; import { SE3Pose, Vec3, Box3WithFrame } from "./geometry"; import { RequestHeader, ResponseHeader } from "./header"; import _m0 from "protobufjs/minimal"; export const protobufPackage = "bosdyn.api"; /** Payloads are defined relative to a frame on the robot. These are the possible frames. */ export enum MountFrameName { /** MOUNT_FRAME_UNKNOWN - The is the default. For backwards compatibility, we assume unknown means body mount frame. */ MOUNT_FRAME_UNKNOWN = 0, /** MOUNT_FRAME_BODY_PAYLOAD - The body payload mount frame, as defined in documentation. */ MOUNT_FRAME_BODY_PAYLOAD = 1, /** MOUNT_FRAME_GRIPPER_PAYLOAD - The gripper payload mount frame, as defined in documentation. */ MOUNT_FRAME_GRIPPER_PAYLOAD = 2, /** MOUNT_FRAME_WR1 - The wrist link frame, as defined in the gripper CAD and documentation. */ MOUNT_FRAME_WR1 = 3, UNRECOGNIZED = -1, } export function mountFrameNameFromJSON(object: any): MountFrameName { switch (object) { case 0: case "MOUNT_FRAME_UNKNOWN": return MountFrameName.MOUNT_FRAME_UNKNOWN; case 1: case "MOUNT_FRAME_BODY_PAYLOAD": return MountFrameName.MOUNT_FRAME_BODY_PAYLOAD; case 2: case "MOUNT_FRAME_GRIPPER_PAYLOAD": return MountFrameName.MOUNT_FRAME_GRIPPER_PAYLOAD; case 3: case "MOUNT_FRAME_WR1": return MountFrameName.MOUNT_FRAME_WR1; case -1: case "UNRECOGNIZED": default: return MountFrameName.UNRECOGNIZED; } } export function mountFrameNameToJSON(object: MountFrameName): string { switch (object) { case MountFrameName.MOUNT_FRAME_UNKNOWN: return "MOUNT_FRAME_UNKNOWN"; case MountFrameName.MOUNT_FRAME_BODY_PAYLOAD: return "MOUNT_FRAME_BODY_PAYLOAD"; case MountFrameName.MOUNT_FRAME_GRIPPER_PAYLOAD: return "MOUNT_FRAME_GRIPPER_PAYLOAD"; case MountFrameName.MOUNT_FRAME_WR1: return "MOUNT_FRAME_WR1"; case MountFrameName.UNRECOGNIZED: default: return "UNRECOGNIZED"; } } /** * A Payload describes a single payload installed on the Spot platform. * It includes all external information necessary to represent * the payload to the user as a single record. */ export interface Payload { /** A unique id provided by the payload or auto-generated by the website. */ GUID: string; /** * A human readable name describing this payload. It is provided by the * payload as part of the payload announcement system. */ name: string; /** * A human-readable description string providing more context as to the * function of this payload. It is displayed in UIs. */ description: string; /** A list of labels used to indicate what type of payload this is. */ labelPrefix: string[]; /** * Set true once the payload is authorized by the administrator in the payload webpage. * Must be set to false at registration time. */ isAuthorized: boolean; /** * Set true if the payload is attached to the robot. * Must be set to false at registration time. */ isEnabled: boolean; /** * Set true for payloads registered without their own computers. These records * are all manually entered. */ isNoncomputePayload: boolean; /** Payload version details. */ version: SoftwareVersion | undefined; /** The pose of the payload relative to the body frame. */ bodyTformPayload: SE3Pose | undefined; /** The pose of the payload relative to the mount frame. */ mountTformPayload: SE3Pose | undefined; /** Optional - mount frame_name (if not included, payload is assumed to be in the body mount frame) */ mountFrameName: MountFrameName; /** The mass and volume properties of the payload. */ massVolumeProperties: PayloadMassVolumeProperties | undefined; /** A list of possible physical configurations for the payload. */ presetConfigurations: PayloadPreset[]; } /** The physical configurations for the payload. */ export interface PayloadPreset { /** * A human readable name describing this configuration. It is displayed in * the admin console, but will not overwrite the top level payload name. */ presetName: string; /** * A human-readable description providing context on this configuration. It is * displayed in the admin console. */ description: string; /** The pose of the payload relative to the body frame. */ mountTformPayload: SE3Pose | undefined; /** Optional - mount frame_name (if not included, payload is assumed to be in the body mount frame) */ mountFrameName: MountFrameName; /** The mass and volume properties of the payload. */ massVolumeProperties: PayloadMassVolumeProperties | undefined; /** A list of labels used to indicate what type of payload this is. */ labelPrefix: string[]; } /** * PayloadMassVolumeProperties contain mass and volume information for the payload * in the format that the user interacts with it. It is transmitted to the control * and perception systems and processed there to inform those systems. */ export interface PayloadMassVolumeProperties { /** Total mass of payload in kg. */ totalMass: number; /** Position of the center of mass of the payload in the payload frame. Meters. */ comPosRtPayload: Vec3 | undefined; /** * The moment of inertia of the payload, represented about the payload * center of mass, in the payload frame. Units in [kg*m^2]. */ moiTensor: MomentOfIntertia | undefined; /** * Zero or more bounding boxes indicating the occupied volume of the payload. * These boxes must be represented in the payload frame by specifying * Must have Box3WithFrame.frame_name == "payload". */ boundingBox: Box3WithFrame[]; /** * Joint limits defining limits to range of motion of the hips of the robot, * in order to prevent collisions with the payload. * This field is optional and is only recommended for advanced development * purposes. */ jointLimits: JointLimits[]; } /** * Structure describing the moment of intertia of a body. The xx, yy, zz fields * are the diagonal of the MOI tensor, and the xy, xz, and yz fields are the * off diagonal terms. */ export interface MomentOfIntertia { xx: number; yy: number; zz: number; xy: number; xz: number; yz: number; } /** JointLimits contain hip joint angles where limb to payload collisions occur. */ export interface JointLimits { /** Label identifying the respective limb to which these apply [fr,fl,hr,hl] */ label: string; /** * (hy, hx) coordinates outlining the hip joint limits where collisions occur * between robot hip and payload. Paired vectors must be of equal length. * Angles are measured with actual contact. Appropriate margin will be provided * in software. Radians. * Left legs must have hx > 0. Right legs must have hx < 0. */ hy: number[]; /** All legs must have hy > 1.3. */ hx: number[]; } /** The ListPayloads request message sent to the robot to get all known payloads. */ export interface ListPayloadsRequest { /** Common request header. */ header: RequestHeader | undefined; } /** The ListPayloads response message returns all payloads registered in the robot's directory. */ export interface ListPayloadsResponse { /** Common response header. */ header: ResponseHeader | undefined; /** The returned list of payloads registered in the directory. */ payloads: Payload[]; } function createBasePayload(): Payload { return { GUID: "", name: "", description: "", labelPrefix: [], isAuthorized: false, isEnabled: false, isNoncomputePayload: false, version: undefined, bodyTformPayload: undefined, mountTformPayload: undefined, mountFrameName: 0, massVolumeProperties: undefined, presetConfigurations: [], }; } export const Payload = { encode( message: Payload, writer: _m0.Writer = _m0.Writer.create() ): _m0.Writer { if (message.GUID !== "") { writer.uint32(10).string(message.GUID); } if (message.name !== "") { writer.uint32(18).string(message.name); } if (message.description !== "") { writer.uint32(26).string(message.description); } for (const v of message.labelPrefix) { writer.uint32(74).string(v!); } if (message.isAuthorized === true) { writer.uint32(32).bool(message.isAuthorized); } if (message.isEnabled === true) { writer.uint32(40).bool(message.isEnabled); } if (message.isNoncomputePayload === true) { writer.uint32(48).bool(message.isNoncomputePayload); } if (message.version !== undefined) { SoftwareVersion.encode( message.version, writer.uint32(98).fork() ).ldelim(); } if (message.bodyTformPayload !== undefined) { SE3Pose.encode( message.bodyTformPayload, writer.uint32(58).fork() ).ldelim(); } if (message.mountTformPayload !== undefined) { SE3Pose.encode( message.mountTformPayload, writer.uint32(66).fork() ).ldelim(); } if (message.mountFrameName !== 0) { writer.uint32(104).int32(message.mountFrameName); } if (message.massVolumeProperties !== undefined) { PayloadMassVolumeProperties.encode( message.massVolumeProperties, writer.uint32(82).fork() ).ldelim(); } for (const v of message.presetConfigurations) { PayloadPreset.encode(v!, writer.uint32(90).fork()).ldelim(); } return writer; }, decode(input: _m0.Reader | Uint8Array, length?: number): Payload { const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBasePayload(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.GUID = reader.string(); break; case 2: message.name = reader.string(); break; case 3: message.description = reader.string(); break; case 9: message.labelPrefix.push(reader.string()); break; case 4: message.isAuthorized = reader.bool(); break; case 5: message.isEnabled = reader.bool(); break; case 6: message.isNoncomputePayload = reader.bool(); break; case 12: message.version = SoftwareVersion.decode(reader, reader.uint32()); break; case 7: message.bodyTformPayload = SE3Pose.decode(reader, reader.uint32()); break; case 8: message.mountTformPayload = SE3Pose.decode(reader, reader.uint32()); break; case 13: message.mountFrameName = reader.int32() as any; break; case 10: message.massVolumeProperties = PayloadMassVolumeProperties.decode( reader, reader.uint32() ); break; case 11: message.presetConfigurations.push( PayloadPreset.decode(reader, reader.uint32()) ); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object: any): Payload { return { GUID: isSet(object.GUID) ? String(object.GUID) : "", name: isSet(object.name) ? String(object.name) : "", description: isSet(object.description) ? String(object.description) : "", labelPrefix: Array.isArray(object?.labelPrefix) ? object.labelPrefix.map((e: any) => String(e)) : [], isAuthorized: isSet(object.isAuthorized) ? Boolean(object.isAuthorized) : false, isEnabled: isSet(object.isEnabled) ? Boolean(object.isEnabled) : false, isNoncomputePayload: isSet(object.isNoncomputePayload) ? Boolean(object.isNoncomputePayload) : false, version: isSet(object.version) ? SoftwareVersion.fromJSON(object.version) : undefined, bodyTformPayload: isSet(object.bodyTformPayload) ? SE3Pose.fromJSON(object.bodyTformPayload) : undefined, mountTformPayload: isSet(object.mountTformPayload) ? SE3Pose.fromJSON(object.mountTformPayload) : undefined, mountFrameName: isSet(object.mountFrameName) ? mountFrameNameFromJSON(object.mountFrameName) : 0, massVolumeProperties: isSet(object.massVolumeProperties) ? PayloadMassVolumeProperties.fromJSON(object.massVolumeProperties) : undefined, presetConfigurations: Array.isArray(object?.presetConfigurations) ? object.presetConfigurations.map((e: any) => PayloadPreset.fromJSON(e)) : [], }; }, toJSON(message: Payload): unknown { const obj: any = {}; message.GUID !== undefined && (obj.GUID = message.GUID); message.name !== undefined && (obj.name = message.name); message.description !== undefined && (obj.description = message.description); if (message.labelPrefix) { obj.labelPrefix = message.labelPrefix.map((e) => e); } else { obj.labelPrefix = []; } message.isAuthorized !== undefined && (obj.isAuthorized = message.isAuthorized); message.isEnabled !== undefined && (obj.isEnabled = message.isEnabled); message.isNoncomputePayload !== undefined && (obj.isNoncomputePayload = message.isNoncomputePayload); message.version !== undefined && (obj.version = message.version ? SoftwareVersion.toJSON(message.version) : undefined); message.bodyTformPayload !== undefined && (obj.bodyTformPayload = message.bodyTformPayload ? SE3Pose.toJSON(message.bodyTformPayload) : undefined); message.mountTformPayload !== undefined && (obj.mountTformPayload = message.mountTformPayload ? SE3Pose.toJSON(message.mountTformPayload) : undefined); message.mountFrameName !== undefined && (obj.mountFrameName = mountFrameNameToJSON(message.mountFrameName)); message.massVolumeProperties !== undefined && (obj.massVolumeProperties = message.massVolumeProperties ? PayloadMassVolumeProperties.toJSON(message.massVolumeProperties) : undefined); if (message.presetConfigurations) { obj.presetConfigurations = message.presetConfigurations.map((e) => e ? PayloadPreset.toJSON(e) : undefined ); } else { obj.presetConfigurations = []; } return obj; }, fromPartial, I>>(object: I): Payload { const message = createBasePayload(); message.GUID = object.GUID ?? ""; message.name = object.name ?? ""; message.description = object.description ?? ""; message.labelPrefix = object.labelPrefix?.map((e) => e) || []; message.isAuthorized = object.isAuthorized ?? false; message.isEnabled = object.isEnabled ?? false; message.isNoncomputePayload = object.isNoncomputePayload ?? false; message.version = object.version !== undefined && object.version !== null ? SoftwareVersion.fromPartial(object.version) : undefined; message.bodyTformPayload = object.bodyTformPayload !== undefined && object.bodyTformPayload !== null ? SE3Pose.fromPartial(object.bodyTformPayload) : undefined; message.mountTformPayload = object.mountTformPayload !== undefined && object.mountTformPayload !== null ? SE3Pose.fromPartial(object.mountTformPayload) : undefined; message.mountFrameName = object.mountFrameName ?? 0; message.massVolumeProperties = object.massVolumeProperties !== undefined && object.massVolumeProperties !== null ? PayloadMassVolumeProperties.fromPartial(object.massVolumeProperties) : undefined; message.presetConfigurations = object.presetConfigurations?.map((e) => PayloadPreset.fromPartial(e)) || []; return message; }, }; function createBasePayloadPreset(): PayloadPreset { return { presetName: "", description: "", mountTformPayload: undefined, mountFrameName: 0, massVolumeProperties: undefined, labelPrefix: [], }; } export const PayloadPreset = { encode( message: PayloadPreset, writer: _m0.Writer = _m0.Writer.create() ): _m0.Writer { if (message.presetName !== "") { writer.uint32(10).string(message.presetName); } if (message.description !== "") { writer.uint32(18).string(message.description); } if (message.mountTformPayload !== undefined) { SE3Pose.encode( message.mountTformPayload, writer.uint32(26).fork() ).ldelim(); } if (message.mountFrameName !== 0) { writer.uint32(48).int32(message.mountFrameName); } if (message.massVolumeProperties !== undefined) { PayloadMassVolumeProperties.encode( message.massVolumeProperties, writer.uint32(34).fork() ).ldelim(); } for (const v of message.labelPrefix) { writer.uint32(42).string(v!); } return writer; }, decode(input: _m0.Reader | Uint8Array, length?: number): PayloadPreset { const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBasePayloadPreset(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.presetName = reader.string(); break; case 2: message.description = reader.string(); break; case 3: message.mountTformPayload = SE3Pose.decode(reader, reader.uint32()); break; case 6: message.mountFrameName = reader.int32() as any; break; case 4: message.massVolumeProperties = PayloadMassVolumeProperties.decode( reader, reader.uint32() ); break; case 5: message.labelPrefix.push(reader.string()); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object: any): PayloadPreset { return { presetName: isSet(object.presetName) ? String(object.presetName) : "", description: isSet(object.description) ? String(object.description) : "", mountTformPayload: isSet(object.mountTformPayload) ? SE3Pose.fromJSON(object.mountTformPayload) : undefined, mountFrameName: isSet(object.mountFrameName) ? mountFrameNameFromJSON(object.mountFrameName) : 0, massVolumeProperties: isSet(object.massVolumeProperties) ? PayloadMassVolumeProperties.fromJSON(object.massVolumeProperties) : undefined, labelPrefix: Array.isArray(object?.labelPrefix) ? object.labelPrefix.map((e: any) => String(e)) : [], }; }, toJSON(message: PayloadPreset): unknown { const obj: any = {}; message.presetName !== undefined && (obj.presetName = message.presetName); message.description !== undefined && (obj.description = message.description); message.mountTformPayload !== undefined && (obj.mountTformPayload = message.mountTformPayload ? SE3Pose.toJSON(message.mountTformPayload) : undefined); message.mountFrameName !== undefined && (obj.mountFrameName = mountFrameNameToJSON(message.mountFrameName)); message.massVolumeProperties !== undefined && (obj.massVolumeProperties = message.massVolumeProperties ? PayloadMassVolumeProperties.toJSON(message.massVolumeProperties) : undefined); if (message.labelPrefix) { obj.labelPrefix = message.labelPrefix.map((e) => e); } else { obj.labelPrefix = []; } return obj; }, fromPartial, I>>( object: I ): PayloadPreset { const message = createBasePayloadPreset(); message.presetName = object.presetName ?? ""; message.description = object.description ?? ""; message.mountTformPayload = object.mountTformPayload !== undefined && object.mountTformPayload !== null ? SE3Pose.fromPartial(object.mountTformPayload) : undefined; message.mountFrameName = object.mountFrameName ?? 0; message.massVolumeProperties = object.massVolumeProperties !== undefined && object.massVolumeProperties !== null ? PayloadMassVolumeProperties.fromPartial(object.massVolumeProperties) : undefined; message.labelPrefix = object.labelPrefix?.map((e) => e) || []; return message; }, }; function createBasePayloadMassVolumeProperties(): PayloadMassVolumeProperties { return { totalMass: 0, comPosRtPayload: undefined, moiTensor: undefined, boundingBox: [], jointLimits: [], }; } export const PayloadMassVolumeProperties = { encode( message: PayloadMassVolumeProperties, writer: _m0.Writer = _m0.Writer.create() ): _m0.Writer { if (message.totalMass !== 0) { writer.uint32(21).float(message.totalMass); } if (message.comPosRtPayload !== undefined) { Vec3.encode(message.comPosRtPayload, writer.uint32(26).fork()).ldelim(); } if (message.moiTensor !== undefined) { MomentOfIntertia.encode( message.moiTensor, writer.uint32(34).fork() ).ldelim(); } for (const v of message.boundingBox) { Box3WithFrame.encode(v!, writer.uint32(42).fork()).ldelim(); } for (const v of message.jointLimits) { JointLimits.encode(v!, writer.uint32(50).fork()).ldelim(); } return writer; }, decode( input: _m0.Reader | Uint8Array, length?: number ): PayloadMassVolumeProperties { const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBasePayloadMassVolumeProperties(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 2: message.totalMass = reader.float(); break; case 3: message.comPosRtPayload = Vec3.decode(reader, reader.uint32()); break; case 4: message.moiTensor = MomentOfIntertia.decode(reader, reader.uint32()); break; case 5: message.boundingBox.push( Box3WithFrame.decode(reader, reader.uint32()) ); break; case 6: message.jointLimits.push(JointLimits.decode(reader, reader.uint32())); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object: any): PayloadMassVolumeProperties { return { totalMass: isSet(object.totalMass) ? Number(object.totalMass) : 0, comPosRtPayload: isSet(object.comPosRtPayload) ? Vec3.fromJSON(object.comPosRtPayload) : undefined, moiTensor: isSet(object.moiTensor) ? MomentOfIntertia.fromJSON(object.moiTensor) : undefined, boundingBox: Array.isArray(object?.boundingBox) ? object.boundingBox.map((e: any) => Box3WithFrame.fromJSON(e)) : [], jointLimits: Array.isArray(object?.jointLimits) ? object.jointLimits.map((e: any) => JointLimits.fromJSON(e)) : [], }; }, toJSON(message: PayloadMassVolumeProperties): unknown { const obj: any = {}; message.totalMass !== undefined && (obj.totalMass = message.totalMass); message.comPosRtPayload !== undefined && (obj.comPosRtPayload = message.comPosRtPayload ? Vec3.toJSON(message.comPosRtPayload) : undefined); message.moiTensor !== undefined && (obj.moiTensor = message.moiTensor ? MomentOfIntertia.toJSON(message.moiTensor) : undefined); if (message.boundingBox) { obj.boundingBox = message.boundingBox.map((e) => e ? Box3WithFrame.toJSON(e) : undefined ); } else { obj.boundingBox = []; } if (message.jointLimits) { obj.jointLimits = message.jointLimits.map((e) => e ? JointLimits.toJSON(e) : undefined ); } else { obj.jointLimits = []; } return obj; }, fromPartial, I>>( object: I ): PayloadMassVolumeProperties { const message = createBasePayloadMassVolumeProperties(); message.totalMass = object.totalMass ?? 0; message.comPosRtPayload = object.comPosRtPayload !== undefined && object.comPosRtPayload !== null ? Vec3.fromPartial(object.comPosRtPayload) : undefined; message.moiTensor = object.moiTensor !== undefined && object.moiTensor !== null ? MomentOfIntertia.fromPartial(object.moiTensor) : undefined; message.boundingBox = object.boundingBox?.map((e) => Box3WithFrame.fromPartial(e)) || []; message.jointLimits = object.jointLimits?.map((e) => JointLimits.fromPartial(e)) || []; return message; }, }; function createBaseMomentOfIntertia(): MomentOfIntertia { return { xx: 0, yy: 0, zz: 0, xy: 0, xz: 0, yz: 0 }; } export const MomentOfIntertia = { encode( message: MomentOfIntertia, writer: _m0.Writer = _m0.Writer.create() ): _m0.Writer { if (message.xx !== 0) { writer.uint32(21).float(message.xx); } if (message.yy !== 0) { writer.uint32(29).float(message.yy); } if (message.zz !== 0) { writer.uint32(37).float(message.zz); } if (message.xy !== 0) { writer.uint32(45).float(message.xy); } if (message.xz !== 0) { writer.uint32(53).float(message.xz); } if (message.yz !== 0) { writer.uint32(61).float(message.yz); } return writer; }, decode(input: _m0.Reader | Uint8Array, length?: number): MomentOfIntertia { const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseMomentOfIntertia(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 2: message.xx = reader.float(); break; case 3: message.yy = reader.float(); break; case 4: message.zz = reader.float(); break; case 5: message.xy = reader.float(); break; case 6: message.xz = reader.float(); break; case 7: message.yz = reader.float(); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object: any): MomentOfIntertia { return { xx: isSet(object.xx) ? Number(object.xx) : 0, yy: isSet(object.yy) ? Number(object.yy) : 0, zz: isSet(object.zz) ? Number(object.zz) : 0, xy: isSet(object.xy) ? Number(object.xy) : 0, xz: isSet(object.xz) ? Number(object.xz) : 0, yz: isSet(object.yz) ? Number(object.yz) : 0, }; }, toJSON(message: MomentOfIntertia): unknown { const obj: any = {}; message.xx !== undefined && (obj.xx = message.xx); message.yy !== undefined && (obj.yy = message.yy); message.zz !== undefined && (obj.zz = message.zz); message.xy !== undefined && (obj.xy = message.xy); message.xz !== undefined && (obj.xz = message.xz); message.yz !== undefined && (obj.yz = message.yz); return obj; }, fromPartial, I>>( object: I ): MomentOfIntertia { const message = createBaseMomentOfIntertia(); message.xx = object.xx ?? 0; message.yy = object.yy ?? 0; message.zz = object.zz ?? 0; message.xy = object.xy ?? 0; message.xz = object.xz ?? 0; message.yz = object.yz ?? 0; return message; }, }; function createBaseJointLimits(): JointLimits { return { label: "", hy: [], hx: [] }; } export const JointLimits = { encode( message: JointLimits, writer: _m0.Writer = _m0.Writer.create() ): _m0.Writer { if (message.label !== "") { writer.uint32(18).string(message.label); } writer.uint32(26).fork(); for (const v of message.hy) { writer.float(v); } writer.ldelim(); writer.uint32(34).fork(); for (const v of message.hx) { writer.float(v); } writer.ldelim(); return writer; }, decode(input: _m0.Reader | Uint8Array, length?: number): JointLimits { const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseJointLimits(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 2: message.label = reader.string(); break; case 3: if ((tag & 7) === 2) { const end2 = reader.uint32() + reader.pos; while (reader.pos < end2) { message.hy.push(reader.float()); } } else { message.hy.push(reader.float()); } break; case 4: if ((tag & 7) === 2) { const end2 = reader.uint32() + reader.pos; while (reader.pos < end2) { message.hx.push(reader.float()); } } else { message.hx.push(reader.float()); } break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object: any): JointLimits { return { label: isSet(object.label) ? String(object.label) : "", hy: Array.isArray(object?.hy) ? object.hy.map((e: any) => Number(e)) : [], hx: Array.isArray(object?.hx) ? object.hx.map((e: any) => Number(e)) : [], }; }, toJSON(message: JointLimits): unknown { const obj: any = {}; message.label !== undefined && (obj.label = message.label); if (message.hy) { obj.hy = message.hy.map((e) => e); } else { obj.hy = []; } if (message.hx) { obj.hx = message.hx.map((e) => e); } else { obj.hx = []; } return obj; }, fromPartial, I>>( object: I ): JointLimits { const message = createBaseJointLimits(); message.label = object.label ?? ""; message.hy = object.hy?.map((e) => e) || []; message.hx = object.hx?.map((e) => e) || []; return message; }, }; function createBaseListPayloadsRequest(): ListPayloadsRequest { return { header: undefined }; } export const ListPayloadsRequest = { encode( message: ListPayloadsRequest, writer: _m0.Writer = _m0.Writer.create() ): _m0.Writer { if (message.header !== undefined) { RequestHeader.encode(message.header, writer.uint32(10).fork()).ldelim(); } return writer; }, decode(input: _m0.Reader | Uint8Array, length?: number): ListPayloadsRequest { const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseListPayloadsRequest(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.header = RequestHeader.decode(reader, reader.uint32()); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object: any): ListPayloadsRequest { return { header: isSet(object.header) ? RequestHeader.fromJSON(object.header) : undefined, }; }, toJSON(message: ListPayloadsRequest): unknown { const obj: any = {}; message.header !== undefined && (obj.header = message.header ? RequestHeader.toJSON(message.header) : undefined); return obj; }, fromPartial, I>>( object: I ): ListPayloadsRequest { const message = createBaseListPayloadsRequest(); message.header = object.header !== undefined && object.header !== null ? RequestHeader.fromPartial(object.header) : undefined; return message; }, }; function createBaseListPayloadsResponse(): ListPayloadsResponse { return { header: undefined, payloads: [] }; } export const ListPayloadsResponse = { encode( message: ListPayloadsResponse, writer: _m0.Writer = _m0.Writer.create() ): _m0.Writer { if (message.header !== undefined) { ResponseHeader.encode(message.header, writer.uint32(10).fork()).ldelim(); } for (const v of message.payloads) { Payload.encode(v!, writer.uint32(18).fork()).ldelim(); } return writer; }, decode( input: _m0.Reader | Uint8Array, length?: number ): ListPayloadsResponse { const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input); let end = length === undefined ? reader.len : reader.pos + length; const message = createBaseListPayloadsResponse(); while (reader.pos < end) { const tag = reader.uint32(); switch (tag >>> 3) { case 1: message.header = ResponseHeader.decode(reader, reader.uint32()); break; case 2: message.payloads.push(Payload.decode(reader, reader.uint32())); break; default: reader.skipType(tag & 7); break; } } return message; }, fromJSON(object: any): ListPayloadsResponse { return { header: isSet(object.header) ? ResponseHeader.fromJSON(object.header) : undefined, payloads: Array.isArray(object?.payloads) ? object.payloads.map((e: any) => Payload.fromJSON(e)) : [], }; }, toJSON(message: ListPayloadsResponse): unknown { const obj: any = {}; message.header !== undefined && (obj.header = message.header ? ResponseHeader.toJSON(message.header) : undefined); if (message.payloads) { obj.payloads = message.payloads.map((e) => e ? Payload.toJSON(e) : undefined ); } else { obj.payloads = []; } return obj; }, fromPartial, I>>( object: I ): ListPayloadsResponse { const message = createBaseListPayloadsResponse(); message.header = object.header !== undefined && object.header !== null ? ResponseHeader.fromPartial(object.header) : undefined; message.payloads = object.payloads?.map((e) => Payload.fromPartial(e)) || []; return message; }, }; type Builtin = | Date | Function | Uint8Array | string | number | boolean | undefined; export type DeepPartial = T extends Builtin ? T : T extends Array ? Array> : T extends ReadonlyArray ? ReadonlyArray> : T extends {} ? { [K in keyof T]?: DeepPartial } : Partial; type KeysOfUnion = T extends T ? keyof T : never; export type Exact = P extends Builtin ? P : P & { [K in keyof P]: Exact } & { [K in Exclude>]: never; }; function isSet(value: any): boolean { return value !== null && value !== undefined; }