Class PivotAscopeDisplay
java.lang.Object
com.flarerobotics.lib.ascope.rotational.PivotAscopeDisplay
Simulates an arm / pivot and calculates joint positions, publishing them to Network Tables
(via Akit Logger) for visualization in AdvantageScope.
Note: Use PivotAscopeDisplay(String, Supplier, double, Supplier)
with length = 0
for a pivot display.
-
Constructor Summary
ConstructorsConstructorDescriptionPivotAscopeDisplay
(String name, Supplier<edu.wpi.first.math.geometry.Pose3d> basePose, double[] segmentLengthsMeters, Supplier<edu.wpi.first.math.geometry.Rotation3d[]> jointAnglesRads, Supplier<Double[]> extensionSupplier) Constructs a new PivotAscopeDisplay.PivotAscopeDisplay
(String name, Supplier<edu.wpi.first.math.geometry.Pose3d> basePose, double length, Supplier<edu.wpi.first.math.geometry.Rotation3d> angleSupplier) Constructs a new single-jointed PivotAscopeDisplay.PivotAscopeDisplay
(String name, Supplier<edu.wpi.first.math.geometry.Pose3d> basePose, double length, Supplier<edu.wpi.first.math.geometry.Rotation3d> angleSupplier, Supplier<Double> extensionSupplier) Constructs a single-jointed new PivotAscopeDisplay. -
Method Summary
Modifier and TypeMethodDescriptionSupplier<edu.wpi.first.math.geometry.Pose3d>
attachMechanism
(Supplier<edu.wpi.first.math.geometry.Transform3d> offset) Attaches a mechanism to end of the arm.edu.wpi.first.math.geometry.Pose3d
Computes the final pose of the arm's end effector using forward kinematics.edu.wpi.first.math.geometry.Pose3d
computeEndEffectorPose
(edu.wpi.first.math.geometry.Transform3d offset) Computes the final pose of the arm's end effector using forward kinematics.edu.wpi.first.math.geometry.Pose3d
getJointPose
(int joint) Returns the pose of the specified joint (1-indexed).edu.wpi.first.math.geometry.Pose3d
getJointPose
(int joint, edu.wpi.first.math.geometry.Transform3d offset) Returns the pose of the specified joint (1-indexed).void
update()
Updates the Network Table outputs.void
update
(edu.wpi.first.math.geometry.Transform3d offset) Updates the Network Table outputs.void
update
(edu.wpi.first.math.geometry.Transform3d[] offsets) Updates the Network Table outputs.
-
Constructor Details
-
PivotAscopeDisplay
public PivotAscopeDisplay(String name, Supplier<edu.wpi.first.math.geometry.Pose3d> basePose, double[] segmentLengthsMeters, Supplier<edu.wpi.first.math.geometry.Rotation3d[]> jointAnglesRads, Supplier<Double[]> extensionSupplier) Constructs a new PivotAscopeDisplay.- Parameters:
name
- The name of the system.basePose
- The pose supplier for the root of the arm.segmentLengthsMeters
- The length of each joint. Must have the same length as the joint angles and the extension supplier, and the joint count.jointAnglesRads
- The supplier for the joint angles, in radians.extensionSupplier
- The extensions supplier in meters, used for telescoping / extending arms.- Throws:
IllegalArgumentException
- If the array lengths don't match.
-
PivotAscopeDisplay
public PivotAscopeDisplay(String name, Supplier<edu.wpi.first.math.geometry.Pose3d> basePose, double length, Supplier<edu.wpi.first.math.geometry.Rotation3d> angleSupplier, Supplier<Double> extensionSupplier) Constructs a single-jointed new PivotAscopeDisplay.- Parameters:
name
- The name of the system.basePose
- The pose supplier for the root of the arm.length
- The length of the arm in meters.angleSupplier
- The supplier for the arm angle, in radians.extensionSupplier
- The extensions supplier in meters, used for telescoping / extending arms.- Throws:
IllegalArgumentException
- If the array lengths don't match.
-
PivotAscopeDisplay
public PivotAscopeDisplay(String name, Supplier<edu.wpi.first.math.geometry.Pose3d> basePose, double length, Supplier<edu.wpi.first.math.geometry.Rotation3d> angleSupplier) Constructs a new single-jointed PivotAscopeDisplay.Note: Use length = 0 for pivot.
- Parameters:
name
- The name of the system.basePose
- The pose supplier for the root of the arm.length
- The length of the arm in meters.angleSupplier
- The supplier for the arm angle, in radians.
-
-
Method Details
-
computeEndEffectorPose
public edu.wpi.first.math.geometry.Pose3d computeEndEffectorPose()Computes the final pose of the arm's end effector using forward kinematics.- Returns:
- The pose of the end effector.
-
computeEndEffectorPose
public edu.wpi.first.math.geometry.Pose3d computeEndEffectorPose(edu.wpi.first.math.geometry.Transform3d offset) Computes the final pose of the arm's end effector using forward kinematics.- Parameters:
offset
- The offset applied to the final position.- Returns:
- The pose of the end effector.
-
getJointPose
public edu.wpi.first.math.geometry.Pose3d getJointPose(int joint, edu.wpi.first.math.geometry.Transform3d offset) Returns the pose of the specified joint (1-indexed). Joint 1 is the first joint (i.e. the transformation after the base, including the first segment's rotation and translation).- Parameters:
joint
- The joint number. (1-indexed)offset
- The offset applied to the final position.- Returns:
- The pose of that joint, computed using forward kinematics.
- Throws:
IllegalArgumentException
- if the joint number is invalid.
-
getJointPose
public edu.wpi.first.math.geometry.Pose3d getJointPose(int joint) Returns the pose of the specified joint (1-indexed). Joint 1 is the first joint (i.e. the transformation after the base, including the first segment's rotation and translation).- Parameters:
joint
- The joint number. (1-indexed)- Returns:
- The pose of that joint, computed using forward kinematics.
- Throws:
IllegalArgumentException
- if the joint number is invalid.
-
update
public void update(edu.wpi.first.math.geometry.Transform3d offset) Updates the Network Table outputs. Data is stored in the path as a Pose3d:Simulation/{SYSTEM_NAME}Arm/Joint{I}/Pose
- Parameters:
offset
- The offset to apply to each joint.
-
update
public void update(edu.wpi.first.math.geometry.Transform3d[] offsets) Updates the Network Table outputs. Data is stored in the path as a Pose3d:Simulation/{SYSTEM_NAME}Arm/Joint{I}/Pose
- Parameters:
offsets
- The offsets to apply to each joint.
-
update
public void update()Updates the Network Table outputs. Data is stored in the path as a Pose3d:Simulation/{SYSTEM_NAME}Arm/Joint{I}/Pose
-
attachMechanism
public Supplier<edu.wpi.first.math.geometry.Pose3d> attachMechanism(Supplier<edu.wpi.first.math.geometry.Transform3d> offset) Attaches a mechanism to end of the arm.- Parameters:
offset
- The offset from the end, uses a supplier because attached mechanisms generally move or rotate. Generally used to supply rotational offsets.- Returns:
- The pose supplier.
-