Package synapse
Class SynapseCamera
java.lang.Object
synapse.SynapseCamera
Represents a Synapse camera with fully cached NetworkTables entries, type-safe settings, and
methods for retrieving results and metrics.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic final classStandardized NetworkTables topic keys for pipelines, results, recording, and latency.static final classRepresents a typed Synapse setting that can be stored in a NetworkTable. -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected final StringCamera nameprotected NetworkTableEntryEntry for tracking the latency of frame capture (in milliseconds)protected NetworkTableSubtable containing camera data/resultsprotected final Map<String,NetworkTableEntry> Cache of all NetworkTableEntries for quick accessprotected NetworkTableEntryCached entry for the current pipeline IDprotected NetworkTableEntryEntry for storing or retrieving the camera's current pipeline typeprotected NetworkTableEntryEntry for tracking the latency of frame processing (in milliseconds)protected NetworkTableEntryEntry that indicates whether recording is currently activeprotected NetworkTableEntryEntry for storing the latest processing results from the cameraprotected Transform3dTransform representing the physical offset between the robot's coordinate frame and the camera's coordinate frame.protected NetworkTableSubtable containing camera settingsprotected NetworkTableRoot table for this cameraprotected static final com.fasterxml.jackson.databind.ObjectMapperObjectMapper configured for MessagePack serialization/deserializationfinal StringName of the Synapse NetworkTables table -
Constructor Summary
ConstructorsConstructorDescriptionSynapseCamera(String cameraName) Constructs a new SynapseCamera using the default coprocessor table name "Synapse".SynapseCamera(String cameraName, String coprocessorName) Constructs a new SynapseCamera with a specific coprocessor table name. -
Method Summary
Modifier and TypeMethodDescriptionestimateRobotPose(Pose3d cameraPose) Converts a given camera pose into a robot pose using the configured robot-to-camera offset.getCachedEntry(String key, NetworkTable table) Retrieves a cached NetworkTableEntry for a given key.Returns the camera name.doubleReturns the latest capture latency in milliseconds.protected NetworkTableReturns the data/results subtable.longReturns the current pipeline ID or -1 if unset.Returns the pipeline type string.doubleReturns the latest processing latency in milliseconds.booleanReturns whether the camera is currently recording.<T> Optional<T>getResults(com.fasterxml.jackson.core.type.TypeReference<T> typeref, byte[] data) Deserialize results from serialized MessagePack data.<T> Optional<T>getResults(SynapsePipelineType<T> pipelineType) Retrieve and deserialize results from the given pipeline.protected NetworkTableEntryReturns the results entry.Returns the transform offset from the robot frame to the camera frame.getSetting(String key) Deprecated, for removal: This API element is subject to removal in a future version.<T> Optional<T>getSetting(SynapseCamera.Setting<T> setting) Typed getter for camera settings.protected NetworkTableReturns the settings subtable.static booleanChecks whether the current execution is in a JUnit or TestNG test.voidsetPipeline(long pipeline) Sets the current pipeline ID.voidsetRecordStatus(boolean status) Sets the camera recording status.voidsetRobotToCameraOffset(Transform3d robotToCameraOffset) Assigns the transform offset between the robot and camera coordinate frames.<T> voidsetSetting(SynapseCamera.Setting<T> setting, T value) Typed setter for camera settings.withRobotToCameraOffset(Transform3d robotToCameraOffset) Sets the transform offset between the robot reference frame and the camera, and returns this instance for chaining.
-
Field Details
-
m_cameraName
Camera name -
synapseTableName
Name of the Synapse NetworkTables table -
m_table
Root table for this camera -
m_settingsTable
Subtable containing camera settings -
m_dataTable
Subtable containing camera data/results -
m_entryCache
Cache of all NetworkTableEntries for quick access -
m_pipelineEntry
Cached entry for the current pipeline ID -
m_pipelineTypeEntry
Entry for storing or retrieving the camera's current pipeline type -
m_resultsEntry
Entry for storing the latest processing results from the camera -
m_recordStateEntry
Entry that indicates whether recording is currently active -
m_captureLatencyEntry
Entry for tracking the latency of frame capture (in milliseconds) -
m_processLatencyEntry
Entry for tracking the latency of frame processing (in milliseconds) -
s_ObjectMapper
protected static final com.fasterxml.jackson.databind.ObjectMapper s_ObjectMapperObjectMapper configured for MessagePack serialization/deserialization -
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
Constructs a new SynapseCamera using the default coprocessor table name "Synapse".- Parameters:
cameraName- the camera's name
-
SynapseCamera
Constructs a new SynapseCamera with a specific coprocessor table name.- Parameters:
cameraName- the camera's namecoprocessorName- the NetworkTables root table for this camera
-
-
Method Details
-
withRobotToCameraOffset
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
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
Returns the transform offset from the robot frame to the camera frame.- Returns:
- the robot-to-camera Transform3d, or null if not configured
-
estimateRobotPose
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
Returns the settings subtable.- Returns:
- the NetworkTable storing camera settings
-
getDataTable
Returns the data/results subtable.- Returns:
- the NetworkTable storing camera results
-
getCachedEntry
Retrieves a cached NetworkTableEntry for a given key.- Parameters:
key- the entry keytable- 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
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, 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
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
Typed setter for camera settings.- Type Parameters:
T- type of the value- Parameters:
setting- the typed settingvalue- the value to set
-
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 typedata- serialized data- Returns:
- Optional containing deserialized results
-
getResults
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
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
-