mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
Added more Talon SRX documentation and PID samples.
Change-Id: I2b1326c11452c6895846ded1277dbf4d38a5222d
This commit is contained in:
@@ -1,35 +1,37 @@
|
||||
#include "WPILib.h"
|
||||
|
||||
/**
|
||||
* This is a quick sample program to show how to use the new Talon SRX over CAN.
|
||||
* As of the time of this writing (11/20/14), the only mode supported on the SRX is the
|
||||
* straight-up throttle (status info, such as current and temperature should work).
|
||||
* This sample shows how to use the new CANTalon to just run a motor in a basic
|
||||
* throttle mode, in the same manner as you might control a traditional PWM
|
||||
* controlled motor.
|
||||
*
|
||||
*/
|
||||
class Robot : public SampleRobot {
|
||||
CANTalon m_motor;
|
||||
|
||||
// update every 0.005 seconds/5 milliseconds.
|
||||
double kUpdatePeriod = 0.005;
|
||||
Joystick m_stick;
|
||||
|
||||
// update every 0.01 seconds/10 milliseconds.
|
||||
// The talon only receives control packets every 10ms.
|
||||
double kUpdatePeriod = 0.010;
|
||||
|
||||
public:
|
||||
Robot()
|
||||
: m_motor(1) // Initialize the Talon as device 1. Use the roboRIO web
|
||||
: m_motor(1), // Initialize the Talon as device 1. Use the roboRIO web
|
||||
// interface to change the device number on the talons.
|
||||
m_stick(0)
|
||||
{}
|
||||
|
||||
/**
|
||||
* Runs the motor from the output of a Joystick.
|
||||
*/
|
||||
void OperatorControl() {
|
||||
m_motor.EnableControl();
|
||||
while (IsOperatorControl() && IsEnabled()) {
|
||||
// Takes a number from -1.0 (full reverse) to +1.0 (full forwards).
|
||||
m_motor.Set(0.5);
|
||||
m_motor.Set(m_stick.GetY());
|
||||
|
||||
Wait(kUpdatePeriod); // Wait 5ms for the next update.
|
||||
Wait(kUpdatePeriod); // Wait a bit so that the loop doesn't lock everything up.
|
||||
}
|
||||
m_motor.Set(0.0);
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
@@ -0,0 +1,63 @@
|
||||
#include "WPILib.h"
|
||||
|
||||
/**
|
||||
* This is a quick sample program to show how to use the new Talon SRX over CAN.
|
||||
* This particular sample demonstrates running a basic PID control loop with an
|
||||
* analog potentiometer.
|
||||
*
|
||||
*/
|
||||
class Robot : public SampleRobot {
|
||||
CANTalon m_motor;
|
||||
|
||||
public:
|
||||
Robot()
|
||||
: m_motor(1) // Initialize the Talon as device 1. Use the roboRIO web
|
||||
// interface to change the device number on the m_motors.
|
||||
{
|
||||
// This sets the mode of the m_motor. The options are:
|
||||
// kPercentVbus: basic throttle; no closed-loop.
|
||||
// kCurrent: Runs the motor with the specified current if possible.
|
||||
// kSpeed: Runs a PID control loop to keep the motor going at a constant
|
||||
// speed using the specified sensor.
|
||||
// kPosition: Runs a PID control loop to move the motor to a specified move
|
||||
// the motor to a specified sensor position.
|
||||
// kVoltage: Runs the m_motor at a constant voltage, if possible.
|
||||
// kFollower: The m_motor will run at the same throttle as the specified other talon.
|
||||
m_motor.SetControlMode(CANSpeedController::kPosition);
|
||||
// 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.
|
||||
m_motor.SetFeedbackDevice(CANTalon::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 (SetSensorDirection 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.
|
||||
m_motor.SetPID(1.0, 0.0, 0.0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs the motor from the output of a Joystick.
|
||||
*/
|
||||
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.
|
||||
m_motor.Set(512);
|
||||
|
||||
Wait(5.0);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
START_ROBOT_CLASS(Robot);
|
||||
@@ -145,6 +145,23 @@
|
||||
</files>
|
||||
</example>
|
||||
|
||||
<example>
|
||||
<name>CAN Talon SRX PID</name>
|
||||
<description>Quick demo of running the SRX with a PID loop.</description>
|
||||
<tags>
|
||||
<tag>Robot and Motor</tag>
|
||||
<tag>Digital</tag>
|
||||
<tag>Actuators</tag>
|
||||
<tag>Complete List</tag>
|
||||
</tags>
|
||||
<packages>
|
||||
<package>src</package>
|
||||
</packages>
|
||||
<files>
|
||||
<file source="examples/CANTalonPID/src/Robot.cpp" destination="src/Robot.cpp"></file>
|
||||
</files>
|
||||
</example>
|
||||
|
||||
<example>
|
||||
<name>Relay</name>
|
||||
<description>Demonstrate controlling a Relay from Joystick buttons.</description>
|
||||
|
||||
Reference in New Issue
Block a user