Skip to content

Commit

Permalink
[wpilib] Improve MotorSafety documentation (NFC) (#4120)
Browse files Browse the repository at this point in the history
Remove OBE RobotDrive porting guide from MecanumDrive
  • Loading branch information
sciencewhiz authored Mar 21, 2022
1 parent 8d79dc8 commit e1b6e5f
Show file tree
Hide file tree
Showing 10 changed files with 33 additions and 21 deletions.
7 changes: 5 additions & 2 deletions wpilibc/src/main/native/include/frc/MotorSafety.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,11 @@
namespace frc {

/**
* This base class runs a watchdog timer and calls the subclass's StopMotor()
* function if the timeout expires.
* The Motor Safety feature acts as a watchdog timer for an individual motor. It
* operates by maintaining a timer that tracks how long it has been since the
* feed() method has been called for that actuator. Code in the Driver Station
* class initiates a comparison of these timers to the timeout values for any
* actuator with safety enabled every 5 received packets (100ms nominal).
*
* The subclass should call Feed() whenever the motor value is updated.
*/
Expand Down
4 changes: 4 additions & 0 deletions wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,10 @@ class SpeedController;
* Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
* so that the full range is still used. This deadband value can be changed
* with SetDeadband().
*
* MotorSafety is enabled by default. The tankDrive, arcadeDrive,
* or curvatureDrive methods should be called periodically to avoid Motor
* Safety timeouts.
*/
class DifferentialDrive : public RobotDriveBase,
public wpi::Sendable,
Expand Down
3 changes: 3 additions & 0 deletions wpilibc/src/main/native/include/frc/drive/KilloughDrive.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@ class SpeedController;
* The positive X axis points ahead, the positive Y axis points right, and the
* and the positive Z axis points down. Rotations follow the right-hand rule, so
* clockwise rotation around the Z axis is positive.
*
* MotorSafety is enabled by default. The DriveCartesian or DrivePolar
* methods should be called periodically to avoid Motor Safety timeouts.
*/
class KilloughDrive : public RobotDriveBase,
public wpi::Sendable,
Expand Down
11 changes: 2 additions & 9 deletions wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,15 +57,8 @@ class SpeedController;
* so that the full range is still used. This deadband value can be changed
* with SetDeadband().
*
* RobotDrive porting guide:
* <br>DriveCartesian(double, double, double, double) is equivalent to
* RobotDrive's MecanumDrive_Cartesian(double, double, double, double)
* if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted
* compared to RobotDrive (eg DriveCartesian(xSpeed, -ySpeed, zRotation,
* -gyroAngle).
* <br>DrivePolar(double, double, double) is equivalent to
* RobotDrive's MecanumDrive_Polar(double, double, double) if a
* deadband of 0 is used.
* MotorSafety is enabled by default. The DriveCartesian or DrivePolar
* methods should be called periodically to avoid Motor Safety timeouts.
*/
class MecanumDrive : public RobotDriveBase,
public wpi::Sendable,
Expand Down
2 changes: 2 additions & 0 deletions wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@ namespace frc {

/**
* Common base class for drive platforms.
*
* MotorSafety is enabled by default.
*/
class RobotDriveBase : public MotorSafety {
public:
Expand Down
6 changes: 4 additions & 2 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,10 @@
import java.util.Set;

/**
* This base class runs a watchdog timer and calls the subclass's StopMotor() function if the
* timeout expires.
* The Motor Safety feature acts as a watchdog timer for an individual motor. It operates by
* maintaining a timer that tracks how long it has been since the feed() method has been called for
* that actuator. Code in the Driver Station class initiates a comparison of these timers to the
* timeout values for any actuator with safety enabled every 5 received packets (100ms nominal).
*
* <p>The subclass should call feed() whenever the motor value is updated.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,9 @@
* <p>Inputs smaller then {@value edu.wpi.first.wpilibj.drive.RobotDriveBase#kDefaultDeadband} will
* be set to 0, and larger values will be scaled so that the full range is still used. This deadband
* value can be changed with {@link #setDeadband}.
*
* <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The tankDrive, arcadeDrive,
* or curvatureDrive methods should be called periodically to avoid Motor Safety timeouts.
*/
@SuppressWarnings("removal")
public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoCloseable {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,9 @@
* <p>The positive X axis points ahead, the positive Y axis points right, and the positive Z axis
* points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is
* positive.
*
* <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The driveCartesian or
* drivePolar methods should be called periodically to avoid Motor Safety timeouts.
*/
@SuppressWarnings("removal")
public class KilloughDrive extends RobotDriveBase implements Sendable, AutoCloseable {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,13 +47,8 @@
* be set to 0, and larger values will be scaled so that the full range is still used. This deadband
* value can be changed with {@link #setDeadband}.
*
* <p>RobotDrive porting guide: <br>
* {@link #driveCartesian(double, double, double, double)} is equivalent to RobotDrive's
* mecanumDrive_Cartesian(double, double, double, double) if a deadband of 0 is used, and the ySpeed
* and gyroAngle values are inverted compared to RobotDrive (eg driveCartesian(xSpeed, -ySpeed,
* zRotation, -gyroAngle). <br>
* {@link #drivePolar(double, double, double)} is equivalent to RobotDrive's
* mecanumDrive_Polar(double, double, double)} if a deadband of 0 is used.
* <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default. The driveCartesian or
* drivePolar methods should be called periodically to avoid Motor Safety timeouts.
*/
@SuppressWarnings("removal")
public class MecanumDrive extends RobotDriveBase implements Sendable, AutoCloseable {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,11 @@
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.MotorSafety;

/** Common base class for drive platforms. */
/**
* Common base class for drive platforms.
*
* <p>{@link edu.wpi.first.wpilibj.MotorSafety} is enabled by default.
*/
public abstract class RobotDriveBase extends MotorSafety {
public static final double kDefaultDeadband = 0.02;
public static final double kDefaultMaxOutput = 1.0;
Expand Down

0 comments on commit e1b6e5f

Please sign in to comment.