mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Added more Talon SRX documentation and PID samples.
Change-Id: I2b1326c11452c6895846ded1277dbf4d38a5222d
This commit is contained in:
@@ -8,31 +8,29 @@ import edu.wpi.first.wpilibj.Timer;
|
||||
|
||||
/**
|
||||
* This is a short sample program demonstrating how to use the basic throttle
|
||||
* mode of the new CAN Talon. As of when this was made, the basic throttle mode
|
||||
* is all that is supported.
|
||||
* mode of the new CAN Talon.
|
||||
*/
|
||||
public class Robot extends SampleRobot {
|
||||
|
||||
CANTalon motor;
|
||||
|
||||
private final double k_updatePeriod = 0.005; // update every 0.005 seconds/5 milliseconds (200Hz)
|
||||
|
||||
public Robot() {
|
||||
motor = new CANTalon(1); // Initialize the CanTalonSRX on device 1.
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs the motor from a joystick.
|
||||
* Runs the motor.
|
||||
*/
|
||||
public void operatorControl() {
|
||||
motor.enableControl();
|
||||
while (isOperatorControl() && isEnabled()) {
|
||||
// Set the motor's output to half power.
|
||||
// This takes a number from -1 (100% speed in reverse) to +1 (100% speed
|
||||
// going forward)
|
||||
motor.set(0.5);
|
||||
|
||||
Timer.delay(k_updatePeriod); // wait 5ms to the next update
|
||||
Timer.delay(0.01); // Note that the CANTalon only receives updates every
|
||||
// 10ms, so updating more quickly would not gain you
|
||||
// anything.
|
||||
}
|
||||
motor.disable();
|
||||
}
|
||||
|
||||
@@ -0,0 +1,62 @@
|
||||
package $package;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj.SpeedController;
|
||||
import edu.wpi.first.wpilibj.CANTalon;
|
||||
import edu.wpi.first.wpilibj.SampleRobot;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
|
||||
/**
|
||||
* This is a short sample program demonstrating how to use the Talon SRX over
|
||||
* CAN to run a closed-loop PID controller with an analog potentiometer.
|
||||
*/
|
||||
public class Robot extends SampleRobot {
|
||||
|
||||
CANTalon motor;
|
||||
|
||||
public Robot() {
|
||||
motor = new CANTalon(1); // Initialize the CanTalonSRX on device 1.
|
||||
|
||||
// This sets the mode of the m_motor. The options are:
|
||||
// PercentVbus: basic throttle; no closed-loop.
|
||||
// Current: Runs the motor with the specified current if possible.
|
||||
// Speed: Runs a PID control loop to keep the motor going at a constant
|
||||
// speed using the specified sensor.
|
||||
// Position: Runs a PID control loop to move the motor to a specified move
|
||||
// the motor to a specified sensor position.
|
||||
// Voltage: Runs the m_motor at a constant voltage, if possible.
|
||||
// Follower: The m_motor will run at the same throttle as the specified
|
||||
// other talon.
|
||||
motor.changeControlMode(CANTalon.ControlMode.Position);
|
||||
// This command allows you to specify which feedback device to use when doing
|
||||
// closed-loop control. The options are:
|
||||
// AnalogPot: Basic analog potentiometer
|
||||
// QuadEncoder: Quadrature Encoder
|
||||
// AnalogEncoder: Analog Encoder
|
||||
// EncRising: Counts the rising edges of the QuadA pin (allows use of a
|
||||
// non-quadrature encoder)
|
||||
// EncFalling: Same as EncRising, but counts on falling edges.
|
||||
motor.setFeedbackDevice(CANTalon.FeedbackDevice.AnalogPot);
|
||||
// This sets the basic P, I , and D values (F, Izone, and rampRate can also
|
||||
// be set, but are ignored here).
|
||||
// These must all be positive floating point numbers (reverseSensor will
|
||||
// multiply the sensor values by negative one in case your sensor is flipped
|
||||
// relative to your motor).
|
||||
// These values are in units of throttle / sensor_units where throttle ranges
|
||||
// from -1023 to +1023 and sensor units are from 0 - 1023 for analog
|
||||
// potentiometers, encoder ticks for encoders, and position / 10ms for
|
||||
// speeds.
|
||||
motor.setPID(1.0, 0.0, 0.0);
|
||||
}
|
||||
|
||||
public void operatorControl() {
|
||||
while (isOperatorControl() && isEnabled()) {
|
||||
// In closed loop mode, this sets the goal in the units mentioned above.
|
||||
// Since we are using an analog potentiometer, this will try to go to
|
||||
// the middle of the potentiometer range.
|
||||
motor.set(512);
|
||||
|
||||
Timer.delay(5.0);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -171,6 +171,23 @@
|
||||
</files>
|
||||
</example>
|
||||
|
||||
<example>
|
||||
<name>CAN Talon SRX PID</name>
|
||||
<description>Demonstrate running a Talon SRX with PID Closed Loop control.</description>
|
||||
<tags>
|
||||
<tag>Actuators</tag>
|
||||
<tag>Complete List</tag>
|
||||
<tag>Robot and Motor</tag>
|
||||
</tags>
|
||||
<packages>
|
||||
<package>src/$package-dir</package>
|
||||
</packages>
|
||||
<files>
|
||||
<file source="examples/CANTalonPID/src/org/usfirst/frc/team190/robot/Robot.java"
|
||||
destination="src/$package-dir/Robot.java"></file>
|
||||
</files>
|
||||
</example>
|
||||
|
||||
|
||||
<tagDescription>
|
||||
<name>CommandBased Robot</name>
|
||||
|
||||
Reference in New Issue
Block a user