Robot Core Documentation
Loading...
Searching...
No Matches
robotCore.apriltags.ApriltagsCamera Class Reference

The ApriltagsCamera class handles communication with the Raspberry Pi Camera. More...

Inheritance diagram for robotCore.apriltags.ApriltagsCamera:
robotCore.Network.NetworkReceiver

Classes

class  ApriltagsCameraRegion
 The ApriltagsCameraRegion specifies a single detected region. More...
 
class  ApriltagsCameraRegions
 The ApriltagsCameraRegions specifies list of detected regions. More...
 
class  ApriltagsCameraStats
 The ApriltagsCameraStats class collects the current camera performance statistics. More...
 
enum  ApriltagsCameraType
 

Public Member Functions

void setCameraInfo (double xOffsetInches, double yOffsetInches, double angleOffsetInDegrees, ApriltagsCameraType type)
 
void disableCameras (boolean disable)
 
boolean isConnected ()
 
void connect (String host, int port)
 
ApriltagsCameraStats getStats ()
 
void clearStats ()
 
ApriltagsCameraRegions getRegions (int cameraNo)
 
boolean isTagVisible ()
 
void processRegions (SwerveDrivePoseEstimator poseEstimator)
 
void setLogging (boolean log)
 
- Public Member Functions inherited from robotCore.Network.NetworkReceiver
void processData (String command)
 

Static Public Member Functions

static double convertTime (long time)
 
static double getTime ()
 
static double normalizeAngle (double angle)
 

Detailed Description

The ApriltagsCamera class handles communication with the Raspberry Pi Camera.

Author
John Gaby

This class allows you to connect to the Data server of the Raspberry Pi and receive information about the image frames processed by the camera.

It also implements a time sync protocol to synchronize the clocks and performs keep-alive functions that detect a disconnect.

Member Function Documentation

◆ clearStats()

void robotCore.apriltags.ApriltagsCamera.clearStats ( )

Clears the camera performance stats

◆ connect()

void robotCore.apriltags.ApriltagsCamera.connect ( String host,
int port )

Connects to the Raspberry Pi Data server

Parameters
host- Specifies IP for the host
port- Specifies the port (default is 5800)

◆ convertTime()

static double robotCore.apriltags.ApriltagsCamera.convertTime ( long time)
static

This converts a specified time from that returned by System.currentTimeMillis() to same time base as returned by getTime()

Returns
Returns the converted time
Parameters
time- Specifies the time in milliseconds.

◆ disableCameras()

void robotCore.apriltags.ApriltagsCamera.disableCameras ( boolean disable)

Disables the processing of the camera data

Parameters
disable- If this value is set to true, the cameras will not update the robot's pose

◆ getRegions()

ApriltagsCameraRegions robotCore.apriltags.ApriltagsCamera.getRegions ( int cameraNo)
Returns
The latest set of camera regions.

Note that the data is received from the camera in a separate thread so calling this twice in a row can generate a different result. Once you retrieve and instance of ApriltagsCameraRegions however, you can be assured that it will NOT be modified when a new frame is received.

◆ getStats()

ApriltagsCameraStats robotCore.apriltags.ApriltagsCamera.getStats ( )

Returns the current camera performance stats

◆ getTime()

static double robotCore.apriltags.ApriltagsCamera.getTime ( )
static
Returns
The current time which has been synchronized with the camera.

◆ isConnected()

boolean robotCore.apriltags.ApriltagsCamera.isConnected ( )
Returns
true if connected to the camera

◆ isTagVisible()

boolean robotCore.apriltags.ApriltagsCamera.isTagVisible ( )
Returns
true if at least one apriltag is visible by either camera

◆ normalizeAngle()

static double robotCore.apriltags.ApriltagsCamera.normalizeAngle ( double angle)
static

This converts the specified angle so that is is between -180 and +180 degrees

Returns
Returns the same angle but guarantees that it is between -180 and +180 degrees.
Parameters
angle- specifies the angle in degrees

◆ processRegions()

void robotCore.apriltags.ApriltagsCamera.processRegions ( SwerveDrivePoseEstimator poseEstimator)

This function processes the apriltags for the current camera frame and updates the robot's position. This should be called from the main loop.

Parameters
poseEstimator- Specifies the poseEstimator that is being used to keep track of the robot's position.

◆ setCameraInfo()

void robotCore.apriltags.ApriltagsCamera.setCameraInfo ( double xOffsetInches,
double yOffsetInches,
double angleOffsetInDegrees,
ApriltagsCameraType type )

Sets the camera position and type for each of the cameras attached to the PI (max of 2 cameras)

Parameters
xOffsetInches- Specifies the x offset of the camera from the center of the robot in inches
yOffsetInches- Specifies the y offset of the camera from the center of the robot in inches
angleOffsetInDegrees- Specifies the orientation of the camera in

◆ setLogging()

void robotCore.apriltags.ApriltagsCamera.setLogging ( boolean log)

This enables/disables extensive logging to file

Parameters
log- If true, log the camera info to a file.

The documentation for this class was generated from the following file: