Package synapse

Class SynapseCamera

java.lang.Object
synapse.SynapseCamera

public class SynapseCamera extends Object
Represents a Synapse camera with fully cached NetworkTables entries, type-safe settings, and methods for retrieving results and metrics.
  • Field Details

    • m_cameraName

      protected final String m_cameraName
      Camera name
    • synapseTableName

      public final String synapseTableName
      Name of the Synapse NetworkTables table
    • m_table

      protected NetworkTable m_table
      Root table for this camera
    • m_settingsTable

      protected NetworkTable m_settingsTable
      Subtable containing camera settings
    • m_dataTable

      protected NetworkTable m_dataTable
      Subtable containing camera data/results
    • m_entryCache

      protected final Map<String,NetworkTableEntry> m_entryCache
      Cache of all NetworkTableEntries for quick access
    • m_pipelineEntry

      protected NetworkTableEntry m_pipelineEntry
      Cached entry for the current pipeline ID
    • m_pipelineTypeEntry

      protected NetworkTableEntry m_pipelineTypeEntry
      Entry for storing or retrieving the camera's current pipeline type
    • m_resultsEntry

      protected NetworkTableEntry m_resultsEntry
      Entry for storing the latest processing results from the camera
    • m_recordStateEntry

      protected NetworkTableEntry m_recordStateEntry
      Entry that indicates whether recording is currently active
    • m_captureLatencyEntry

      protected NetworkTableEntry m_captureLatencyEntry
      Entry for tracking the latency of frame capture (in milliseconds)
    • m_processLatencyEntry

      protected NetworkTableEntry m_processLatencyEntry
      Entry for tracking the latency of frame processing (in milliseconds)
    • s_ObjectMapper

      protected static final com.fasterxml.jackson.databind.ObjectMapper s_ObjectMapper
      ObjectMapper configured for MessagePack serialization/deserialization
    • m_robotToCameraOffset

      protected Transform3d m_robotToCameraOffset
      Transform representing the physical offset between the robot's coordinate frame and the camera's coordinate frame.

      This is used to convert between camera poses and robot poses, where the transform defines the camera's position and orientation relative to the robot.

  • Constructor Details

    • SynapseCamera

      public SynapseCamera(String cameraName)
      Constructs a new SynapseCamera using the default coprocessor table name "Synapse".
      Parameters:
      cameraName - the camera's name
    • SynapseCamera

      public SynapseCamera(String cameraName, String coprocessorName)
      Constructs a new SynapseCamera with a specific coprocessor table name.
      Parameters:
      cameraName - the camera's name
      coprocessorName - the NetworkTables root table for this camera
  • Method Details

    • withRobotToCameraOffset

      public SynapseCamera withRobotToCameraOffset(Transform3d robotToCameraOffset)
      Sets the transform offset between the robot reference frame and the camera, and returns this instance for chaining.

      The offset defines where the camera is located relative to the robot, enabling conversion between camera poses and robot poses.

      Parameters:
      robotToCameraOffset - the transform from robot space to camera space
      Returns:
      this SynapseCamera instance for fluent chaining
    • setRobotToCameraOffset

      public void setRobotToCameraOffset(Transform3d robotToCameraOffset)
      Assigns the transform offset between the robot and camera coordinate frames.

      This offset is used when estimating robot pose based on camera pose measurements.

      Parameters:
      robotToCameraOffset - the transform from robot to camera
    • getRobotToCameraOffset

      public Transform3d getRobotToCameraOffset()
      Returns the transform offset from the robot frame to the camera frame.
      Returns:
      the robot-to-camera Transform3d, or null if not configured
    • estimateRobotPose

      public Pose3d estimateRobotPose(Pose3d cameraPose)
      Converts a given camera pose into a robot pose using the configured robot-to-camera offset.

      This performs the inverse transform of the stored offset and applies it to the camera pose, yielding an estimated robot pose in the same coordinate frame.

      Parameters:
      cameraPose - the camera pose in a shared coordinate system
      Returns:
      estimated robot pose
      Throws:
      NullPointerException - if the offset has not been set
    • getSettingsTable

      protected NetworkTable getSettingsTable()
      Returns the settings subtable.
      Returns:
      the NetworkTable storing camera settings
    • getDataTable

      protected NetworkTable getDataTable()
      Returns the data/results subtable.
      Returns:
      the NetworkTable storing camera results
    • getCachedEntry

      public NetworkTableEntry getCachedEntry(String key, NetworkTable table)
      Retrieves a cached NetworkTableEntry for a given key.
      Parameters:
      key - the entry key
      table - the table to fetch the entry from
      Returns:
      the cached or newly fetched NetworkTableEntry
    • getPipeline

      public long getPipeline()
      Returns the current pipeline ID or -1 if unset.
      Returns:
      the pipeline index
    • setPipeline

      public void setPipeline(long pipeline)
      Sets the current pipeline ID.
      Parameters:
      pipeline - pipeline index
    • getPipelineType

      public String getPipelineType()
      Returns the pipeline type string.
      Returns:
      the pipeline type
    • getRecordingStatus

      public boolean getRecordingStatus()
      Returns whether the camera is currently recording.
      Returns:
      true if recording, false otherwise
    • setRecordStatus

      public void setRecordStatus(boolean status)
      Sets the camera recording status.
      Parameters:
      status - true to start recording, false to stop
    • getCaptureLatency

      public double getCaptureLatency()
      Returns the latest capture latency in milliseconds.
      Returns:
      capture latency
    • getProcessLatency

      public double getProcessLatency()
      Returns the latest processing latency in milliseconds.
      Returns:
      processing latency
    • getSetting

      @Deprecated(forRemoval=true, since="2025.0.1") public Optional<Object> getSetting(String key)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Deprecated untyped setting retrieval.
      Parameters:
      key - the setting key
      Returns:
      an Optional containing the value if present
    • getSetting

      public <T> Optional<T> getSetting(SynapseCamera.Setting<T> setting)
      Typed getter for camera settings.
      Type Parameters:
      T - the value type
      Parameters:
      setting - the typed setting
      Returns:
      Optional containing value if present and type matches
    • setSetting

      public <T> void setSetting(SynapseCamera.Setting<T> setting, T value)
      Typed setter for camera settings.
      Type Parameters:
      T - type of the value
      Parameters:
      setting - the typed setting
      value - the value to set
    • getResultsEntry

      protected NetworkTableEntry getResultsEntry()
      Returns the results entry.
      Returns:
      cached results NetworkTableEntry
    • getResults

      public <T> Optional<T> getResults(com.fasterxml.jackson.core.type.TypeReference<T> typeref, byte[] data)
      Deserialize results from serialized MessagePack data.
      Type Parameters:
      T - type of the result
      Parameters:
      typeref - TypeReference describing the expected type
      data - serialized data
      Returns:
      Optional containing deserialized results
    • getResults

      public <T> Optional<T> getResults(SynapsePipelineType<T> pipelineType)
      Retrieve and deserialize results from the given pipeline.

      This method fetches the raw serialized results for the specified pipeline, and deserializes them using the pipeline's associated TypeReference.

      Type Parameters:
      T - type of the result
      Parameters:
      pipelineType - the pipeline type whose results are to be retrieved
      Returns:
      Optional containing deserialized results if available, otherwise empty
    • getCameraName

      public String getCameraName()
      Returns the camera name.
      Returns:
      camera name
    • isJUnitTest

      public static boolean isJUnitTest()
      Checks whether the current execution is in a JUnit or TestNG test.
      Returns:
      true if running inside a test framework