mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Update ArmSimulation example to use Mechanism2d (#3572)
- Correct several comments that referenced elevator - Changed noise to be 1 encoder tick instead of half a degree - Changed gear ratio and PID value to be better tuned - Updated bounds to be similar to a single jointed arm
This commit is contained in:
@@ -12,7 +12,13 @@
|
||||
#include <frc/simulation/EncoderSim.h>
|
||||
#include <frc/simulation/RoboRioSim.h>
|
||||
#include <frc/simulation/SingleJointedArmSim.h>
|
||||
#include <frc/smartdashboard/Mechanism2d.h>
|
||||
#include <frc/smartdashboard/MechanismLigament2d.h>
|
||||
#include <frc/smartdashboard/MechanismRoot2d.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <frc/system/plant/LinearSystemId.h>
|
||||
#include <frc/util/Color.h>
|
||||
#include <frc/util/Color8Bit.h>
|
||||
#include <units/angle.h>
|
||||
#include <units/moment_of_inertia.h>
|
||||
#include <wpi/numbers>
|
||||
@@ -28,14 +34,14 @@ class Robot : public frc::TimedRobot {
|
||||
static constexpr int kJoystickPort = 0;
|
||||
|
||||
// The P gain for the PID controller that drives this arm.
|
||||
static constexpr double kArmKp = 5.0;
|
||||
static constexpr double kArmKp = 50.0;
|
||||
|
||||
// distance per pulse = (angle per revolution) / (pulses per revolution)
|
||||
// = (2 * PI rads) / (4096 pulses)
|
||||
static constexpr double kArmEncoderDistPerPulse =
|
||||
2.0 * wpi::numbers::pi / 4096.0;
|
||||
|
||||
// The arm gearbox represents a gerbox containing two Vex 775pro motors.
|
||||
// The arm gearbox represents a gearbox containing two Vex 775pro motors.
|
||||
frc::DCMotor m_armGearbox = frc::DCMotor::Vex775Pro(2);
|
||||
|
||||
// Standard classes for controlling our arm
|
||||
@@ -45,24 +51,36 @@ class Robot : public frc::TimedRobot {
|
||||
frc::Joystick m_joystick{kJoystickPort};
|
||||
|
||||
// Simulation classes help us simulate what's going on, including gravity.
|
||||
// This sim represents an arm with 2 775s, a 100:1 reduction, a mass of 5kg,
|
||||
// 30in overall arm length, range of motion nin [-180, 0] degrees, and noise
|
||||
// with a standard deviation of 0.5 degrees.
|
||||
// This sim represents an arm with 2 775s, a 600:1 reduction, a mass of 5kg,
|
||||
// 30in overall arm length, range of motion in [-75, 255] degrees, and noise
|
||||
// with a standard deviation of 1 encoder tick.
|
||||
frc::sim::SingleJointedArmSim m_armSim{
|
||||
m_armGearbox,
|
||||
100.0,
|
||||
600.0,
|
||||
frc::sim::SingleJointedArmSim::EstimateMOI(30_in, 5_kg),
|
||||
30_in,
|
||||
-180_deg,
|
||||
0_deg,
|
||||
-75_deg,
|
||||
255_deg,
|
||||
5_kg,
|
||||
true,
|
||||
{(0.5_deg).to<double>()}};
|
||||
{kArmEncoderDistPerPulse}};
|
||||
frc::sim::EncoderSim m_encoderSim{m_encoder};
|
||||
|
||||
// Create a Mechanism2d display of an Arm
|
||||
frc::Mechanism2d m_mech2d{60, 60};
|
||||
frc::MechanismRoot2d* m_armBase = m_mech2d.GetRoot("ArmBase", 30, 30);
|
||||
frc::MechanismLigament2d* m_armTower =
|
||||
m_armBase->Append<frc::MechanismLigament2d>(
|
||||
"Arm Tower", 30, -90_deg, 6, frc::Color8Bit{frc::Color::kBlue});
|
||||
frc::MechanismLigament2d* m_arm = m_armBase->Append<frc::MechanismLigament2d>(
|
||||
"Arm", 30, m_armSim.GetAngle(), 6, frc::Color8Bit{frc::Color::kYellow});
|
||||
|
||||
public:
|
||||
void RobotInit() override {
|
||||
m_encoder.SetDistancePerPulse(kArmEncoderDistPerPulse);
|
||||
|
||||
// Put Mechanism 2d to SmartDashboard
|
||||
frc::SmartDashboard::PutData("Arm Sim", &m_mech2d);
|
||||
}
|
||||
|
||||
void SimulationPeriodic() override {
|
||||
@@ -80,13 +98,17 @@ class Robot : public frc::TimedRobot {
|
||||
// SimBattery estimates loaded battery voltages
|
||||
frc::sim::RoboRioSim::SetVInVoltage(
|
||||
frc::sim::BatterySim::Calculate({m_armSim.GetCurrentDraw()}));
|
||||
|
||||
// Update the Mechanism Arm angle based on the simulated arm angle
|
||||
m_arm->SetAngle(m_armSim.GetAngle());
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
if (m_joystick.GetTrigger()) {
|
||||
// Here, we run PID control like normal, with a constant setpoint of 30in.
|
||||
double pidOutput =
|
||||
m_controller.Calculate(m_encoder.GetDistance(), (30_in).to<double>());
|
||||
// Here, we run PID control like normal, with a constant setpoint of 75
|
||||
// degrees.
|
||||
double pidOutput = m_controller.Calculate(
|
||||
m_encoder.GetDistance(), (units::radian_t(75_deg)).to<double>());
|
||||
m_motor.SetVoltage(units::volt_t(pidOutput));
|
||||
} else {
|
||||
// Otherwise, we disable the motor.
|
||||
|
||||
@@ -701,7 +701,8 @@
|
||||
"Digital",
|
||||
"Sensors",
|
||||
"Simulation",
|
||||
"Physics"
|
||||
"Physics",
|
||||
"Mechanism2d"
|
||||
],
|
||||
"foldername": "ArmSimulation",
|
||||
"gradlebase": "cpp",
|
||||
|
||||
Reference in New Issue
Block a user