import { FoxgloveEnumSchema, FoxgloveMessageSchema } from "./types"; const Color: FoxgloveMessageSchema = { type: "message", name: "Color", description: "A color in RGBA format", fields: [ { name: "r", type: { type: "primitive", name: "float64" }, description: "Red value between 0 and 1", defaultValue: 1.0, }, { name: "g", type: { type: "primitive", name: "float64" }, description: "Green value between 0 and 1", defaultValue: 1.0, }, { name: "b", type: { type: "primitive", name: "float64" }, description: "Blue value between 0 and 1", defaultValue: 1.0, }, { name: "a", type: { type: "primitive", name: "float64" }, description: "Alpha value between 0 and 1", defaultValue: 1.0, }, ], }; const Vector2: FoxgloveMessageSchema = { type: "message", name: "Vector2", description: "A vector in 2D space that represents a direction only", fields: [ { name: "x", type: { type: "primitive", name: "float64" }, description: "x coordinate length", defaultValue: 1.0, }, { name: "y", type: { type: "primitive", name: "float64" }, description: "y coordinate length", defaultValue: 1.0, }, ], }; const Vector3: FoxgloveMessageSchema = { type: "message", name: "Vector3", description: "A vector in 3D space that represents a direction only", rosEquivalent: "geometry_msgs/Vector3", fields: [ { name: "x", type: { type: "primitive", name: "float64" }, description: "x coordinate length", defaultValue: 1.0, }, { name: "y", type: { type: "primitive", name: "float64" }, description: "y coordinate length", defaultValue: 1.0, }, { name: "z", type: { type: "primitive", name: "float64" }, description: "z coordinate length", defaultValue: 1.0, }, ], }; const Point2: FoxgloveMessageSchema = { type: "message", name: "Point2", description: "A point representing a position in 2D space", fields: [ { name: "x", type: { type: "primitive", name: "float64" }, description: "x coordinate position", }, { name: "y", type: { type: "primitive", name: "float64" }, description: "y coordinate position", }, ], }; const Point3: FoxgloveMessageSchema = { type: "message", name: "Point3", description: "A point representing a position in 3D space", rosEquivalent: "geometry_msgs/Point", fields: [ { name: "x", type: { type: "primitive", name: "float64" }, description: "x coordinate position", }, { name: "y", type: { type: "primitive", name: "float64" }, description: "y coordinate position", }, { name: "z", type: { type: "primitive", name: "float64" }, description: "z coordinate position", }, ], }; const Quaternion: FoxgloveMessageSchema = { type: "message", name: "Quaternion", description: "A [quaternion](https://eater.net/quaternions) representing a rotation in 3D space", rosEquivalent: "geometry_msgs/Quaternion", fields: [ { name: "x", type: { type: "primitive", name: "float64" }, description: "x value", }, { name: "y", type: { type: "primitive", name: "float64" }, description: "y value", }, { name: "z", type: { type: "primitive", name: "float64" }, description: "z value", }, { name: "w", type: { type: "primitive", name: "float64" }, description: "w value", defaultValue: 1.0, }, ], }; const Pose: FoxgloveMessageSchema = { type: "message", name: "Pose", description: "A position and orientation for an object or reference frame in 3D space", rosEquivalent: "geometry_msgs/Pose", fields: [ { name: "position", type: { type: "nested", schema: Vector3 }, description: "Point denoting position in 3D space", }, { name: "orientation", type: { type: "nested", schema: Quaternion }, description: "Quaternion denoting orientation in 3D space", }, ], }; const KeyValuePair: FoxgloveMessageSchema = { type: "message", name: "KeyValuePair", description: "A key with its associated value", fields: [ { name: "key", type: { type: "primitive", name: "string" }, description: "Key", }, { name: "value", type: { type: "primitive", name: "string" }, description: "Value", }, ], }; const SceneEntityDeletionType: FoxgloveEnumSchema = { type: "enum", name: "SceneEntityDeletionType", parentSchemaName: "SceneEntityDeletion", protobufEnumName: "Type", description: "An enumeration indicating which entities should match a SceneEntityDeletion command", values: [ { value: 0, name: "MATCHING_ID", description: "Delete the existing entity on the same topic that has the provided `id`", }, { value: 1, name: "ALL", description: "Delete all existing entities on the same topic" }, ], }; const SceneEntityDeletion: FoxgloveMessageSchema = { type: "message", name: "SceneEntityDeletion", description: "Command to remove previously published entities", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of the deletion. Only matching entities earlier than this timestamp will be deleted.", }, { name: "type", type: { type: "enum", enum: SceneEntityDeletionType }, description: "Type of deletion action to perform", }, { name: "id", type: { type: "primitive", name: "string" }, description: "Identifier which must match if `type` is `MATCHING_ID`.", }, ], }; const ArrowPrimitive: FoxgloveMessageSchema = { type: "message", name: "ArrowPrimitive", description: "A primitive representing an arrow", fields: [ { name: "pose", type: { type: "nested", schema: Pose }, description: "Position of the arrow's tail and orientation of the arrow. Identity orientation means the arrow points in the +x direction.", }, { name: "shaft_length", type: { type: "primitive", name: "float64" }, description: "Length of the arrow shaft", }, { name: "shaft_diameter", type: { type: "primitive", name: "float64" }, description: "Diameter of the arrow shaft", }, { name: "head_length", type: { type: "primitive", name: "float64" }, description: "Length of the arrow head", }, { name: "head_diameter", type: { type: "primitive", name: "float64" }, description: "Diameter of the arrow head", }, { name: "color", type: { type: "nested", schema: Color }, description: "Color of the arrow", }, ], }; const CubePrimitive: FoxgloveMessageSchema = { type: "message", name: "CubePrimitive", description: "A primitive representing a cube or rectangular prism", fields: [ { name: "pose", type: { type: "nested", schema: Pose }, description: "Position of the center of the cube and orientation of the cube", }, { name: "size", type: { type: "nested", schema: Vector3 }, description: "Size of the cube along each axis", }, { name: "color", type: { type: "nested", schema: Color }, description: "Color of the cube", }, ], }; const SpherePrimitive: FoxgloveMessageSchema = { type: "message", name: "SpherePrimitive", description: "A primitive representing a sphere or ellipsoid", fields: [ { name: "pose", type: { type: "nested", schema: Pose }, description: "Position of the center of the sphere and orientation of the sphere", }, { name: "size", type: { type: "nested", schema: Vector3 }, description: "Size (diameter) of the sphere along each axis", }, { name: "color", type: { type: "nested", schema: Color }, description: "Color of the sphere", }, ], }; const CylinderPrimitive: FoxgloveMessageSchema = { type: "message", name: "CylinderPrimitive", description: "A primitive representing a cylinder, elliptic cylinder, or truncated cone", fields: [ { name: "pose", type: { type: "nested", schema: Pose }, description: "Position of the center of the cylinder and orientation of the cylinder. The flat face(s) are perpendicular to the z-axis.", }, { name: "size", type: { type: "nested", schema: Vector3 }, description: "Size of the cylinder's bounding box", }, { name: "bottom_scale", type: { type: "primitive", name: "float64" }, description: "0-1, ratio of the diameter of the cylinder's bottom face (min z) to the bottom of the bounding box", }, { name: "top_scale", type: { type: "primitive", name: "float64" }, description: "0-1, ratio of the diameter of the cylinder's top face (max z) to the top of the bounding box", }, { name: "color", type: { type: "nested", schema: Color }, description: "Color of the cylinder", }, ], }; const LineType: FoxgloveEnumSchema = { type: "enum", name: "LineType", parentSchemaName: "LinePrimitive", protobufEnumName: "Type", description: "An enumeration indicating how input points should be interpreted to create lines", values: [ { value: 0, name: "LINE_STRIP", description: "Connected line segments: 0-1, 1-2, ..., (n-1)-n", }, { value: 1, name: "LINE_LOOP", description: "Closed polygon: 0-1, 1-2, ..., (n-1)-n, n-0" }, { value: 2, name: "LINE_LIST", description: "Individual line segments: 0-1, 2-3, 4-5, ..." }, ], }; const LinePrimitive: FoxgloveMessageSchema = { type: "message", name: "LinePrimitive", description: "A primitive representing a series of points connected by lines", fields: [ { name: "type", type: { type: "enum", enum: LineType }, description: "Drawing primitive to use for lines", }, { name: "pose", type: { type: "nested", schema: Pose }, description: "Origin of lines relative to reference frame", }, { name: "thickness", type: { type: "primitive", name: "float64" }, description: "Line thickness", }, { name: "scale_invariant", type: { type: "primitive", name: "boolean" }, description: "Indicates whether `thickness` is a fixed size in screen pixels (true), or specified in world coordinates and scales with distance from the camera (false)", }, { name: "points", type: { type: "nested", schema: Point3 }, array: true, description: "Points along the line", }, { name: "color", type: { type: "nested", schema: Color }, description: "Solid color to use for the whole line. One of `color` or `colors` must be provided.", }, { name: "colors", type: { type: "nested", schema: Color }, array: true, description: "Per-point colors (if specified, must have the same length as `points`). One of `color` or `colors` must be provided.", }, { name: "indices", type: { type: "primitive", name: "uint32" }, array: true, description: "Indices into the `points` and `colors` attribute arrays, which can be used to avoid duplicating attribute data.\n\nIf omitted or empty, indexing will not be used. This default behavior is equivalent to specifying [0, 1, ..., N-1] for the indices (where N is the number of `points` provided).", }, ], }; const TextPrimitive: FoxgloveMessageSchema = { type: "message", name: "TextPrimitive", description: "A primitive representing a text label", fields: [ { name: "pose", type: { type: "nested", schema: Pose }, description: "Position of the center of the text box and orientation of the text. Identity orientation means the text is oriented in the xy-plane and flows from -x to +x.", }, { name: "billboard", type: { type: "primitive", name: "boolean" }, description: "Whether the text should respect `pose.orientation` (false) or always face the camera (true)", }, { name: "font_size", type: { type: "primitive", name: "float64" }, description: "Font size (height of one line of text)", }, { name: "scale_invariant", type: { type: "primitive", name: "boolean" }, description: "Indicates whether `font_size` is a fixed size in screen pixels (true), or specified in world coordinates and scales with distance from the camera (false)", }, { name: "color", type: { type: "nested", schema: Color }, description: "Color of the text", }, { name: "text", type: { type: "primitive", name: "string" }, description: "Text", }, ], }; const TriangleListPrimitive: FoxgloveMessageSchema = { type: "message", name: "TriangleListPrimitive", description: "A primitive representing a set of triangles or a surface tiled by triangles", fields: [ { name: "pose", type: { type: "nested", schema: Pose }, description: "Origin of triangles relative to reference frame", }, { name: "points", type: { type: "nested", schema: Point3 }, array: true, description: "Vertices to use for triangles, interpreted as a list of triples (0-1-2, 3-4-5, ...)", }, { name: "color", type: { type: "nested", schema: Color }, description: "Solid color to use for the whole shape. One of `color` or `colors` must be provided.", }, { name: "colors", type: { type: "nested", schema: Color }, array: true, description: "Per-vertex colors (if specified, must have the same length as `points`). One of `color` or `colors` must be provided.", }, { name: "indices", type: { type: "primitive", name: "uint32" }, array: true, description: "Indices into the `points` and `colors` attribute arrays, which can be used to avoid duplicating attribute data.\n\nIf omitted or empty, indexing will not be used. This default behavior is equivalent to specifying [0, 1, ..., N-1] for the indices (where N is the number of `points` provided).", }, ], }; const ModelPrimitive: FoxgloveMessageSchema = { type: "message", name: "ModelPrimitive", description: "A primitive representing a 3D model file loaded from an external URL or embedded data", fields: [ { name: "pose", type: { type: "nested", schema: Pose }, description: "Origin of model relative to reference frame", }, { name: "scale", type: { type: "nested", schema: Vector3 }, description: "Scale factor to apply to the model along each axis", }, { name: "color", type: { type: "nested", schema: Color }, description: "Solid color to use for the whole model if `override_color` is true.", }, { name: "override_color", type: { type: "primitive", name: "boolean" }, description: "Whether to use the color specified in `color` instead of any materials embedded in the original model.", }, { name: "url", type: { type: "primitive", name: "string" }, description: "URL pointing to model file. One of `url` or `data` should be provided.", }, { name: "media_type", type: { type: "primitive", name: "string" }, description: "[Media type](https://developer.mozilla.org/en-US/docs/Web/HTTP/Basics_of_HTTP/MIME_types) of embedded model (e.g. `model/gltf-binary`). Required if `data` is provided instead of `url`. Overrides the inferred media type if `url` is provided.", }, { name: "data", type: { type: "primitive", name: "bytes" }, description: "Embedded model. One of `url` or `data` should be provided. If `data` is provided, `media_type` must be set to indicate the type of the data.", }, ], }; const SceneEntity: FoxgloveMessageSchema = { type: "message", name: "SceneEntity", description: "A visual element in a 3D scene. An entity may be composed of multiple primitives which all share the same frame of reference.", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of the entity", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference", }, { name: "id", type: { type: "primitive", name: "string" }, description: "Identifier for the entity. A entity will replace any prior entity on the same topic with the same `id`.", }, { name: "lifetime", type: { type: "primitive", name: "duration" }, description: "Length of time (relative to `timestamp`) after which the entity should be automatically removed. Zero value indicates the entity should remain visible until it is replaced or deleted.", }, { name: "frame_locked", type: { type: "primitive", name: "boolean" }, description: "Whether the entity should keep its location in the fixed frame (false) or follow the frame specified in `frame_id` as it moves relative to the fixed frame (true)", }, { name: "metadata", type: { type: "nested", schema: KeyValuePair }, array: true, description: "Additional user-provided metadata associated with the entity. Keys must be unique.", }, { name: "arrows", type: { type: "nested", schema: ArrowPrimitive }, array: true, description: "Arrow primitives", }, { name: "cubes", type: { type: "nested", schema: CubePrimitive }, array: true, description: "Cube primitives", }, { name: "spheres", type: { type: "nested", schema: SpherePrimitive }, array: true, description: "Sphere primitives", }, { name: "cylinders", type: { type: "nested", schema: CylinderPrimitive }, array: true, description: "Cylinder primitives", }, { name: "lines", type: { type: "nested", schema: LinePrimitive }, array: true, description: "Line primitives", }, { name: "triangles", type: { type: "nested", schema: TriangleListPrimitive }, array: true, description: "Triangle list primitives", }, { name: "texts", type: { type: "nested", schema: TextPrimitive }, array: true, description: "Text primitives", }, { name: "models", type: { type: "nested", schema: ModelPrimitive }, array: true, description: "Model primitives", }, ], }; const SceneUpdate: FoxgloveMessageSchema = { type: "message", name: "SceneUpdate", description: "An update to the entities displayed in a 3D scene", fields: [ { name: "deletions", type: { type: "nested", schema: SceneEntityDeletion }, array: true, description: "Scene entities to delete", }, { name: "entities", type: { type: "nested", schema: SceneEntity }, array: true, description: "Scene entities to add or replace", }, ], }; const CameraCalibration: FoxgloveMessageSchema = { type: "message", name: "CameraCalibration", description: "Camera calibration parameters", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of calibration data", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference for the camera. The origin of the frame is the optical center of the camera. +x points to the right in the image, +y points down, and +z points into the plane of the image.", protobufFieldNumber: 9, }, { name: "width", type: { type: "primitive", name: "uint32" }, description: "Image width", }, { name: "height", type: { type: "primitive", name: "uint32" }, description: "Image height", }, { name: "distortion_model", type: { type: "primitive", name: "string" }, description: "Name of distortion model\n\nSupported parameters: `plumb_bob` (k1, k2, p1, p2, k3) and `rational_polynomial` (k1, k2, p1, p2, k3, k4, k5, k6). Distortion models are based on [OpenCV's](https://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html) [pinhole camera model](https://en.wikipedia.org/wiki/Distortion_%28optics%29#Software_correction). This is the same [implementation used by ROS](http://docs.ros.org/en/diamondback/api/image_geometry/html/c++/pinhole__camera__model_8cpp_source.html)", }, { name: "D", type: { type: "primitive", name: "float64" }, description: "Distortion parameters", array: true, }, { name: "K", type: { type: "primitive", name: "float64" }, array: 9, description: `Intrinsic camera matrix (3x3 row-major matrix) A 3x3 row-major matrix for the raw (distorted) image. Projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx, fy) and principal point (cx, cy). \`\`\` [fx 0 cx] K = [ 0 fy cy] [ 0 0 1] \`\`\` `, }, { name: "R", type: { type: "primitive", name: "float64" }, array: 9, description: `Rectification matrix (stereo cameras only, 3x3 row-major matrix) A rotation matrix aligning the camera coordinate system to the ideal stereo image plane so that epipolar lines in both stereo images are parallel.`, }, { name: "P", type: { type: "primitive", name: "float64" }, array: 12, description: `Projection/camera matrix (3x4 row-major matrix) \`\`\` [fx' 0 cx' Tx] P = [ 0 fy' cy' Ty] [ 0 0 1 0] \`\`\` By convention, this matrix specifies the intrinsic (camera) matrix of the processed (rectified) image. That is, the left 3x3 portion is the normal camera intrinsic matrix for the rectified image. It projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx', fy') and principal point (cx', cy') - these may differ from the values in K. For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will also have R = the identity and P[1:3,1:3] = K. For a stereo pair, the fourth column [Tx Ty 0]' is related to the position of the optical center of the second camera in the first camera's frame. We assume Tz = 0 so both cameras are in the same stereo image plane. The first camera always has Tx = Ty = 0. For the right (second) camera of a horizontal stereo pair, Ty = 0 and Tx = -fx' * B, where B is the baseline between the cameras. Given a 3D point [X Y Z]', the projection (x, y) of the point onto the rectified image is given by: \`\`\` [u v w]' = P * [X Y Z 1]' x = u / w y = v / w \`\`\` This holds for both images of a stereo pair. `, }, ], }; const CompressedImage: FoxgloveMessageSchema = { type: "message", name: "CompressedImage", description: "A compressed image", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of image", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference for the image. The origin of the frame is the optical center of the camera. +x points to the right in the image, +y points down, and +z points into the plane of the image.", protobufFieldNumber: 4, }, { name: "data", type: { type: "primitive", name: "bytes" }, description: "Compressed image data", }, { name: "format", type: { type: "primitive", name: "string" }, description: "Image format\n\nSupported values: image media types supported by Chrome, such as `webp`, `jpeg`, `png`", }, ], }; const CompressedVideo: FoxgloveMessageSchema = { type: "message", name: "CompressedVideo", description: "A single frame of a compressed video bitstream", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of video frame", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference for the video.\n\nThe origin of the frame is the optical center of the camera. +x points to the right in the video, +y points down, and +z points into the plane of the video.", }, { name: "data", type: { type: "primitive", name: "bytes" }, description: "Compressed video frame data.\n\nFor packet-based video codecs this data must begin and end on packet boundaries (no partial packets), and must contain enough video packets to decode exactly one image (either a keyframe or delta frame). Note: Foxglove does not support video streams that include B frames because they require lookahead.", }, { name: "format", type: { type: "primitive", name: "string" }, description: "Video format.\n\nSupported values: `h264` (Annex B formatted data only)", }, ], }; const RawImage: FoxgloveMessageSchema = { type: "message", name: "RawImage", description: "A raw image", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of image", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference for the image. The origin of the frame is the optical center of the camera. +x points to the right in the image, +y points down, and +z points into the plane of the image.", protobufFieldNumber: 7, }, { name: "width", type: { type: "primitive", name: "uint32" }, description: "Image width", }, { name: "height", type: { type: "primitive", name: "uint32" }, description: "Image height", }, { name: "encoding", type: { type: "primitive", name: "string" }, description: "Encoding of the raw image data\n\nSupported values: `8UC1`, `8UC3`, `16UC1`, `32FC1`, `bayer_bggr8`, `bayer_gbrg8`, `bayer_grbg8`, `bayer_rggb8`, `bgr8`, `bgra8`, `mono8`, `mono16`, `rgb8`, `rgba8`, `uyvy` or `yuv422`, `yuyv` or `yuv422_yuy2`", }, { name: "step", type: { type: "primitive", name: "uint32" }, description: "Byte length of a single row", }, { name: "data", type: { type: "primitive", name: "bytes" }, description: "Raw image data", }, ], }; const FrameTransform: FoxgloveMessageSchema = { type: "message", name: "FrameTransform", description: "A transform between two reference frames in 3D space", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of transform", }, { name: "parent_frame_id", type: { type: "primitive", name: "string" }, description: "Name of the parent frame", }, { name: "child_frame_id", type: { type: "primitive", name: "string" }, description: "Name of the child frame", }, { name: "translation", type: { type: "nested", schema: Vector3 }, description: "Translation component of the transform", }, { name: "rotation", type: { type: "nested", schema: Quaternion }, description: "Rotation component of the transform", }, ], }; const FrameTransforms: FoxgloveMessageSchema = { type: "message", name: "FrameTransforms", description: "An array of FrameTransform messages", fields: [ { name: "transforms", type: { type: "nested", schema: FrameTransform }, array: true, description: "Array of transforms", }, ], }; const PoseInFrame: FoxgloveMessageSchema = { type: "message", name: "PoseInFrame", description: "A timestamped pose for an object or reference frame in 3D space", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of pose", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference for pose position and orientation", }, { name: "pose", type: { type: "nested", schema: Pose }, description: "Pose in 3D space", }, ], }; const PosesInFrame: FoxgloveMessageSchema = { type: "message", name: "PosesInFrame", description: "An array of timestamped poses for an object or reference frame in 3D space", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of pose", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference for pose position and orientation", }, { name: "poses", type: { type: "nested", schema: Pose }, description: "Poses in 3D space", array: true, }, ], }; const GeoJSON: FoxgloveMessageSchema = { type: "message", name: "GeoJSON", description: "GeoJSON data for annotating maps", fields: [ { name: "geojson", type: { type: "primitive", name: "string" }, description: "GeoJSON data encoded as a UTF-8 string", }, ], }; const NumericType: FoxgloveEnumSchema = { type: "enum", name: "NumericType", description: "Numeric type", parentSchemaName: "PackedElementField", protobufEnumName: "NumericType", values: [ { name: "UNKNOWN", value: 0 }, { name: "UINT8", value: 1 }, { name: "INT8", value: 2 }, { name: "UINT16", value: 3 }, { name: "INT16", value: 4 }, { name: "UINT32", value: 5 }, { name: "INT32", value: 6 }, { name: "FLOAT32", value: 7 }, { name: "FLOAT64", value: 8 }, ], }; const PackedElementField: FoxgloveMessageSchema = { type: "message", name: "PackedElementField", description: "A field present within each element in a byte array of packed elements.", fields: [ { name: "name", type: { type: "primitive", name: "string" }, description: "Name of the field", }, { name: "offset", type: { type: "primitive", name: "uint32" }, description: "Byte offset from start of data buffer", }, { name: "type", type: { type: "enum", enum: NumericType }, description: "Type of data in the field. Integers are stored using little-endian byte order.", }, ], }; const Grid: FoxgloveMessageSchema = { type: "message", name: "Grid", description: "A 2D grid of data", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of grid", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference", }, { name: "pose", type: { type: "nested", schema: Pose }, description: "Origin of grid's corner relative to frame of reference; grid is positioned in the x-y plane relative to this origin", }, { name: "column_count", type: { type: "primitive", name: "uint32" }, description: "Number of grid columns", }, { name: "cell_size", type: { type: "nested", schema: Vector2 }, description: "Size of single grid cell along x and y axes, relative to `pose`", }, { name: "row_stride", type: { type: "primitive", name: "uint32" }, description: "Number of bytes between rows in `data`", }, { name: "cell_stride", type: { type: "primitive", name: "uint32" }, description: "Number of bytes between cells within a row in `data`", }, { name: "fields", type: { type: "nested", schema: PackedElementField }, array: true, description: "Fields in `data`. `red`, `green`, `blue`, and `alpha` are optional for customizing the grid's color.", }, { name: "data", type: { type: "primitive", name: "bytes" }, description: "Grid cell data, interpreted using `fields`, in row-major (y-major) order", }, ], }; const CircleAnnotation: FoxgloveMessageSchema = { type: "message", name: "CircleAnnotation", description: "A circle annotation on a 2D image", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of circle", }, { name: "position", type: { type: "nested", schema: Point2 }, description: "Center of the circle in 2D image coordinates (pixels)", }, { name: "diameter", type: { type: "primitive", name: "float64" }, description: "Circle diameter in pixels", }, { name: "thickness", type: { type: "primitive", name: "float64" }, description: "Line thickness in pixels", }, { name: "fill_color", type: { type: "nested", schema: Color }, description: "Fill color", }, { name: "outline_color", type: { type: "nested", schema: Color }, description: "Outline color", }, ], }; const PointsAnnotationType: FoxgloveEnumSchema = { type: "enum", name: "PointsAnnotationType", description: "Type of points annotation", parentSchemaName: "PointsAnnotation", protobufEnumName: "Type", values: [ { name: "UNKNOWN", value: 0 }, { name: "POINTS", value: 1, description: "Individual points: 0, 1, 2, ..." }, { name: "LINE_LOOP", value: 2, description: "Closed polygon: 0-1, 1-2, ..., (n-1)-n, n-0" }, { name: "LINE_STRIP", value: 3, description: "Connected line segments: 0-1, 1-2, ..., (n-1)-n", }, { name: "LINE_LIST", value: 4, description: "Individual line segments: 0-1, 2-3, 4-5, ..." }, ], }; const PointsAnnotation: FoxgloveMessageSchema = { type: "message", name: "PointsAnnotation", description: "An array of points on a 2D image", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of annotation", }, { name: "type", type: { type: "enum", enum: PointsAnnotationType }, description: "Type of points annotation to draw", }, { name: "points", type: { type: "nested", schema: Point2 }, description: "Points in 2D image coordinates (pixels)", array: true, }, { name: "outline_color", type: { type: "nested", schema: Color }, description: "Outline color", }, { name: "outline_colors", type: { type: "nested", schema: Color }, description: "Per-point colors, if `type` is `POINTS`, or per-segment stroke colors, if `type` is `LINE_LIST`, `LINE_STRIP` or `LINE_LOOP`.", array: true, }, { name: "fill_color", type: { type: "nested", schema: Color }, description: "Fill color", }, { name: "thickness", type: { type: "primitive", name: "float64" }, description: "Stroke thickness in pixels", }, ], }; const TextAnnotation: FoxgloveMessageSchema = { type: "message", name: "TextAnnotation", description: "A text label on a 2D image", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of annotation", }, { name: "position", type: { type: "nested", schema: Point2 }, description: "Bottom-left origin of the text label in 2D image coordinates (pixels)", }, { name: "text", type: { type: "primitive", name: "string" }, description: "Text to display", }, { name: "font_size", type: { type: "primitive", name: "float64" }, description: "Font size in pixels", defaultValue: 12.0, }, { name: "text_color", type: { type: "nested", schema: Color }, description: "Text color", }, { name: "background_color", type: { type: "nested", schema: Color }, description: "Background fill color", }, ], }; const ImageAnnotations: FoxgloveMessageSchema = { type: "message", name: "ImageAnnotations", description: "Array of annotations for a 2D image", fields: [ { name: "circles", type: { type: "nested", schema: CircleAnnotation }, description: "Circle annotations", array: true, }, { name: "points", type: { type: "nested", schema: PointsAnnotation }, description: "Points annotations", array: true, }, { name: "texts", type: { type: "nested", schema: TextAnnotation }, description: "Text annotations", array: true, }, ], }; const PositionCovarianceType: FoxgloveEnumSchema = { type: "enum", name: "PositionCovarianceType", description: "Type of position covariance", parentSchemaName: "LocationFix", protobufEnumName: "PositionCovarianceType", values: [ { name: "UNKNOWN", value: 0 }, { name: "APPROXIMATED", value: 1 }, { name: "DIAGONAL_KNOWN", value: 2 }, { name: "KNOWN", value: 3 }, ], }; const LocationFix: FoxgloveMessageSchema = { type: "message", name: "LocationFix", description: "A navigation satellite fix for any Global Navigation Satellite System", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of the message", protobufFieldNumber: 6, }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame for the sensor. Latitude and longitude readings are at the origin of the frame.", protobufFieldNumber: 7, }, { name: "latitude", type: { type: "primitive", name: "float64" }, description: "Latitude in degrees", protobufFieldNumber: 1, }, { name: "longitude", type: { type: "primitive", name: "float64" }, description: "Longitude in degrees", protobufFieldNumber: 2, }, { name: "altitude", type: { type: "primitive", name: "float64" }, description: "Altitude in meters", protobufFieldNumber: 3, }, { name: "position_covariance", type: { type: "primitive", name: "float64" }, description: "Position covariance (m^2) defined relative to a tangential plane through the reported position. The components are East, North, and Up (ENU), in row-major order.", array: 9, protobufFieldNumber: 4, }, { name: "position_covariance_type", type: { type: "enum", enum: PositionCovarianceType }, description: "If `position_covariance` is available, `position_covariance_type` must be set to indicate the type of covariance.", protobufFieldNumber: 5, }, ], }; const LogLevel: FoxgloveEnumSchema = { type: "enum", name: "LogLevel", description: "Log level", parentSchemaName: "Log", protobufEnumName: "Level", values: [ { name: "UNKNOWN", value: 0 }, { name: "DEBUG", value: 1 }, { name: "INFO", value: 2 }, { name: "WARNING", value: 3 }, { name: "ERROR", value: 4 }, { name: "FATAL", value: 5 }, ], }; const Log: FoxgloveMessageSchema = { type: "message", name: "Log", description: "A log message", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of log message", }, { name: "level", type: { type: "enum", enum: LogLevel }, description: "Log level", }, { name: "message", type: { type: "primitive", name: "string" }, description: "Log message", }, { name: "name", type: { type: "primitive", name: "string" }, description: "Process or node name", }, { name: "file", type: { type: "primitive", name: "string" }, description: "Filename", }, { name: "line", type: { type: "primitive", name: "uint32" }, description: "Line number in the file", }, ], }; const PointCloud: FoxgloveMessageSchema = { type: "message", name: "PointCloud", description: "A collection of N-dimensional points, which may contain additional fields with information like normals, intensity, etc.", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of point cloud", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference", }, { name: "pose", type: { type: "nested", schema: Pose }, description: "The origin of the point cloud relative to the frame of reference", }, { name: "point_stride", type: { type: "primitive", name: "uint32" }, description: "Number of bytes between points in the `data`", }, { name: "fields", type: { type: "nested", schema: PackedElementField }, array: true, description: "Fields in `data`. At least 2 coordinate fields from `x`, `y`, and `z` are required for each point's position; `red`, `green`, `blue`, and `alpha` are optional for customizing each point's color.", }, { name: "data", type: { type: "primitive", name: "bytes" }, description: "Point data, interpreted using `fields`", }, ], }; const LaserScan: FoxgloveMessageSchema = { type: "message", name: "LaserScan", description: "A single scan from a planar laser range-finder", fields: [ { name: "timestamp", type: { type: "primitive", name: "time" }, description: "Timestamp of scan", }, { name: "frame_id", type: { type: "primitive", name: "string" }, description: "Frame of reference", }, { name: "pose", type: { type: "nested", schema: Pose }, description: "Origin of scan relative to frame of reference; points are positioned in the x-y plane relative to this origin; angles are interpreted as counterclockwise rotations around the z axis with 0 rad being in the +x direction", }, { name: "start_angle", type: { type: "primitive", name: "float64" }, description: "Bearing of first point, in radians", }, { name: "end_angle", type: { type: "primitive", name: "float64" }, description: "Bearing of last point, in radians", }, { name: "ranges", type: { type: "primitive", name: "float64" }, description: "Distance of detections from origin; assumed to be at equally-spaced angles between `start_angle` and `end_angle`", array: true, }, { name: "intensities", type: { type: "primitive", name: "float64" }, description: "Intensity of detections", array: true, }, ], }; export const foxgloveMessageSchemas = { ArrowPrimitive, CameraCalibration, CircleAnnotation, Color, CompressedImage, CompressedVideo, CylinderPrimitive, CubePrimitive, FrameTransform, FrameTransforms, GeoJSON, Grid, ImageAnnotations, KeyValuePair, LaserScan, LinePrimitive, LocationFix, Log, SceneEntityDeletion, SceneEntity, SceneUpdate, ModelPrimitive, PackedElementField, Point2, Point3, PointCloud, PointsAnnotation, Pose, PoseInFrame, PosesInFrame, Quaternion, RawImage, SpherePrimitive, TextAnnotation, TextPrimitive, TriangleListPrimitive, Vector2, Vector3, }; export const foxgloveEnumSchemas = { LineType, LogLevel, SceneEntityDeletionType, NumericType, PointsAnnotationType, PositionCovarianceType, };