mirror of
https://github.com/trc492/FtcTemplate.git
synced 2025-07-01 04:51:23 -07:00
Updated subsystem comments.
Made Elevator 2-motor.
This commit is contained in:
@ -30,9 +30,11 @@ import trclib.robotcore.TrcEvent;
|
||||
import trclib.subsystem.TrcSubsystem;
|
||||
|
||||
/**
|
||||
* This class implements an Arm Subsystem. The Arm subsystem consists of a motor with built-in encoder. It does not
|
||||
* This class implements an Arm Subsystem. This implementation consists of a motor with built-in encoder. It does not
|
||||
* have any limit switches, so it is using motor stall detection to zero calibrate the built-in relative encoder. It
|
||||
* supports gravity compensation by computing the power required to hold the arm at its current angle.
|
||||
* There are many possible implementations by setting different parameters.
|
||||
* Please refer to the TrcLib documentation (<a href="https://trc492.github.io">...</a>) for details.
|
||||
*/
|
||||
public class Arm extends TrcSubsystem
|
||||
{
|
||||
|
@ -34,9 +34,11 @@ import trclib.subsystem.TrcServoClaw;
|
||||
import trclib.subsystem.TrcSubsystem;
|
||||
|
||||
/**
|
||||
* This class implements a Claw Subsystem. The Claw subsystem consists of two servos and a sensor to detect the
|
||||
* This class implements a Claw Subsystem. This implementation consists of two servos and a sensor to detect the
|
||||
* presence of an object and can auto grab it. The sensor can be either a digital sensor such as touch sensor or beam
|
||||
* break sensor) or an analog sensor such as a distance sensor.
|
||||
* There are many possible implementations by setting different parameters.
|
||||
* Please refer to the TrcLib documentation (<a href="https://trc492.github.io">...</a>) for details.
|
||||
*/
|
||||
public class Claw extends TrcSubsystem
|
||||
{
|
||||
|
@ -29,12 +29,14 @@ import trclib.subsystem.TrcDifferentialServoWrist;
|
||||
import trclib.subsystem.TrcSubsystem;
|
||||
|
||||
/**
|
||||
* This class creates the Differential Servo Wrist subsystem. The Differential Servo Wrist subsystem is a 2-DOF
|
||||
* system that consists of two servos. When the two servos rotate in the same direction, the wrist will tilt up and
|
||||
* down. When the two servos rotate in opposite direction, the wrist will rotate. Regular servos have a limited
|
||||
* range of movement. Because of this, the tilt and rotation of the wrist will limit each other's range of motion.
|
||||
* For example, if the wrist is tilted to one extreme end, the wrist cannot rotate. If the wrist is in the middle
|
||||
* tilt position, it will have maximum rotation range and vice versa.
|
||||
* This class creates the Differential Servo Wrist subsystem. This implementation is a 2-DOF system that consists of
|
||||
* two servos. When the two servos rotate in the same direction, the wrist will tilt up and down. When the two servos
|
||||
* rotate in opposite direction, the wrist will rotate. Regular servos have a limited range of movement. Because of
|
||||
* this, the tilt and rotation of the wrist will limit each other's range of motion. For example, if the wrist is
|
||||
* tilted to one extreme end, the wrist cannot rotate. If the wrist is in the middle tilt position, it will have
|
||||
* maximum rotation range and vice versa.
|
||||
* There are many possible implementations by setting different parameters.
|
||||
* Please refer to the TrcLib documentation (<a href="https://trc492.github.io">...</a>) for details.
|
||||
*/
|
||||
public class DiffyServoWrist extends TrcSubsystem
|
||||
{
|
||||
|
@ -30,9 +30,11 @@ import trclib.robotcore.TrcEvent;
|
||||
import trclib.subsystem.TrcSubsystem;
|
||||
|
||||
/**
|
||||
* This class implements an Elevator Subsystem. The Elevator subsystem consists of a motor with built-in encoder and
|
||||
* This class implements an Elevator Subsystem. This implementation consists of two motors with built-in encoders and
|
||||
* a lower limit switch for zero calibrating the relative encoder. It supports gravity compensation. In the case of
|
||||
* an elevator, gravity compensation power is the constant power required to hold the elevator at any position.
|
||||
* There are many possible implementations by setting different parameters.
|
||||
* Please refer to the TrcLib documentation (<a href="https://trc492.github.io">...</a>) for details.
|
||||
*/
|
||||
public class Elevator extends TrcSubsystem
|
||||
{
|
||||
@ -41,9 +43,15 @@ public class Elevator extends TrcSubsystem
|
||||
public static final String SUBSYSTEM_NAME = "Elevator";
|
||||
public static final boolean NEED_ZERO_CAL = true;
|
||||
|
||||
public static final String MOTOR_NAME = SUBSYSTEM_NAME + ".motor";
|
||||
public static final FtcMotorActuator.MotorType MOTOR_TYPE= FtcMotorActuator.MotorType.DcMotor;
|
||||
public static final boolean MOTOR_INVERTED = true;
|
||||
public static final String PRIMARY_MOTOR_NAME = SUBSYSTEM_NAME + ".primary";
|
||||
public static final FtcMotorActuator.MotorType PRIMARY_MOTOR_TYPE =
|
||||
FtcMotorActuator.MotorType.DcMotor;
|
||||
public static final boolean PRIMARY_MOTOR_INVERTED = true;
|
||||
|
||||
public static final String FOLLOWER_MOTOR_NAME = SUBSYSTEM_NAME + ".follower";
|
||||
public static final FtcMotorActuator.MotorType FOLLOWER_MOTOR_TYPE =
|
||||
FtcMotorActuator.MotorType.DcMotor;
|
||||
public static final boolean FOLLOWER_MOTOR_INVERTED = true;
|
||||
|
||||
public static final String LOWER_LIMITSW_NAME = SUBSYSTEM_NAME + ".lowerLimitSw";
|
||||
public static final boolean LOWER_LIMITSW_INVERTED = false;
|
||||
@ -79,7 +87,8 @@ public class Elevator extends TrcSubsystem
|
||||
|
||||
dashboard = FtcDashboard.getInstance();
|
||||
FtcMotorActuator.Params motorParams = new FtcMotorActuator.Params()
|
||||
.setPrimaryMotor(Params.MOTOR_NAME, Params.MOTOR_TYPE, Params.MOTOR_INVERTED)
|
||||
.setPrimaryMotor(Params.PRIMARY_MOTOR_NAME, Params.PRIMARY_MOTOR_TYPE, Params.PRIMARY_MOTOR_INVERTED)
|
||||
.setFollowerMotor(Params.FOLLOWER_MOTOR_NAME, Params.FOLLOWER_MOTOR_TYPE, Params.FOLLOWER_MOTOR_INVERTED)
|
||||
.setLowerLimitSwitch(Params.LOWER_LIMITSW_NAME, Params.LOWER_LIMITSW_INVERTED)
|
||||
.setPositionScaleAndOffset(Params.INCHES_PER_COUNT, Params.POS_OFFSET)
|
||||
.setPositionPresets(Params.POS_PRESET_TOLERANCE, Params.posPresets);
|
||||
|
@ -29,9 +29,11 @@ import trclib.robotcore.TrcEvent;
|
||||
import trclib.subsystem.TrcSubsystem;
|
||||
|
||||
/**
|
||||
* This class creates the Servo Wrist subsystem. The Servo Wrist subsystem is a 1-DOF system that consists of a servo.
|
||||
* This class creates the Servo Wrist subsystem. This implementation is a 1-DOF system that consists of a servo.
|
||||
* It allows the wrist to tilt up and down. Regular servos have a limited * range of movement. Therefore, it limits
|
||||
* the tilting range of the wrist.
|
||||
* There are many possible implementations by setting different parameters.
|
||||
* Please refer to the TrcLib documentation (<a href="https://trc492.github.io">...</a>) for details.
|
||||
*/
|
||||
public class ServoWrist extends TrcSubsystem
|
||||
{
|
||||
@ -50,7 +52,6 @@ public class ServoWrist extends TrcSubsystem
|
||||
|
||||
public static final double POS_PRESET_TOLERANCE = 1.0; // in degrees
|
||||
public static final double[] tiltPosPresets = {-110, -90.0, -45.0, 0.0, 45.0, 90.0, 110};
|
||||
public static final double[] rotatePosPresets = {-90.0, -45.0, 0.0, 45.0, 90.0};
|
||||
} //class Params
|
||||
|
||||
private final FtcDashboard dashboard;
|
||||
|
@ -32,13 +32,15 @@ import trclib.subsystem.TrcShooter;
|
||||
import trclib.subsystem.TrcSubsystem;
|
||||
|
||||
/**
|
||||
* This class implements an Shooter Subsystem. The shooter subsystem consists of one or two shooter motors. For
|
||||
* This class implements an Shooter Subsystem. This implementation consists of one or two shooter motors. For
|
||||
* two-motor shooter, the two motors can be arranged to spin in the same direction (2-stage shooting) or in opposite
|
||||
* directions. For opposite spinning motor arrangement, one can spin the motors at different speed to create back spin
|
||||
* when shooting the object. In the two-motor configuration, because the two motors may not be identical (even if they
|
||||
* are the same model), the subsystem allows you to tune different PID coefficients for each motor. The shooter
|
||||
* subsystem also supports optionally mounting on a pan and tilt platform. This allows for aiming the shooter at
|
||||
* the shooting target.
|
||||
* There are many possible implementations by setting different parameters.
|
||||
* Please refer to the TrcLib documentation (<a href="https://trc492.github.io">...</a>) for details.
|
||||
*/
|
||||
public class Shooter extends TrcSubsystem
|
||||
{
|
||||
|
@ -30,11 +30,13 @@ import trclib.robotcore.TrcEvent;
|
||||
import trclib.subsystem.TrcSubsystem;
|
||||
|
||||
/**
|
||||
* This class implements a Turret Subsystem. The Turret subsystem consists of a motor with built-in encoder. It has
|
||||
* This class implements a Turret Subsystem. This implementation consists of a motor with built-in encoder. It has
|
||||
* a lower limit switch for zero calibrating the built-in relative encoder. Since Turret is circular in nature, it
|
||||
* is recommended to implement a hard stop to prevent the Turret from overrunning the upper limit causing the wiring
|
||||
* harness to be twisted. Even though we do implement soft limits on the Turret, hard stop would prevent folks from
|
||||
* spinning the turret round and round twisting the wiring harness when the robot is off.
|
||||
* There are many possible implementations by setting different parameters.
|
||||
* Please refer to the TrcLib documentation (<a href="https://trc492.github.io">...</a>) for details.
|
||||
*/
|
||||
public class Turret extends TrcSubsystem
|
||||
{
|
||||
|
Reference in New Issue
Block a user