Permalink
Please sign in to comment.
Browse files
Fixed the motor tests by reducing speed to within the limits of the e…
…ncoders we use. Also fixed java pid tolerances since getAvgError() was broken. It is now fixed and works properly. Added tests for both java and cpp that test if pid tolerances are working using fake input output pairs. Change-Id: I5bf23dbbdab996c582e1035fc2b2f36dd5f52417
- Loading branch information...
Showing
with
207 additions
and 41 deletions.
- +13 −15 wpilibcIntegrationTests/src/MotorEncoderTest.cpp
- +1 −1 wpilibcIntegrationTests/src/MotorInvertingTest.cpp
- +79 −0 wpilibcIntegrationTests/src/PIDToleranceTest.cpp
- +7 −6 wpilibj/src/shared/java/edu/wpi/first/wpilibj/PIDController.java
- +9 −9 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
- +1 −1 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorInvertingTest.java
- +2 −2 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
- +88 −0 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDToleranceTest.java
- +2 −2 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java
- +3 −3 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANJaguarInversionTest.java
- +1 −1 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANPercentQuadEncoderModeTest.java
- +1 −1 wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANSpeedQuadEncoderModeTest.java
| @@ -0,0 +1,79 @@ | ||
| +/*----------------------------------------------------------------------------*/ | ||
| +/* Copyright (c) FIRST 2014-2016. All Rights Reserved. */ | ||
| +/* Open Source Software - may be modified and shared by FRC teams. The code */ | ||
| +/* must be accompanied by the FIRST BSD license file in the root directory of */ | ||
| +/* the project. */ | ||
| +/*----------------------------------------------------------------------------*/ | ||
| + | ||
| +#include <Timer.h> | ||
| +#include "gtest/gtest.h" | ||
| +#include "TestBench.h" | ||
| +#include "PIDSource.h" | ||
| +#include "PIDController.h" | ||
| +#include "PIDOutput.h" | ||
| + | ||
| +class PIDToleranceTest : public testing::Test{ | ||
| +protected: | ||
| + const double setpoint = 50.0; | ||
| + const double range = 200; | ||
| + const double tolerance = 10.0; | ||
| + class fakeInput : public PIDSource{ | ||
| + public: | ||
| + double val = 0; | ||
| + void SetPIDSourceType(PIDSourceType pidSource){ | ||
| + } | ||
| + PIDSourceType GetPIDSourceType(){ | ||
| + return PIDSourceType::kDisplacement; | ||
| + } | ||
| + double PIDGet(){; | ||
| + return val; | ||
| + } | ||
| + }; | ||
| + class fakeOutput : public PIDOutput{ | ||
| + void PIDWrite(float output){ | ||
| + | ||
| + } | ||
| + }; | ||
| + fakeInput inp; | ||
| + fakeOutput out; | ||
| + PIDController *pid; | ||
| + virtual void SetUp() override { | ||
| + pid = new PIDController(0.5,0.0,0.0,&inp,&out); | ||
| + pid->SetInputRange(-range/2,range/2); | ||
| + } | ||
| + virtual void TearDown() override { | ||
| + delete pid; | ||
| + } | ||
| + virtual void reset(){ | ||
| + inp.val = 0; | ||
| + } | ||
| +}; | ||
| + | ||
| +TEST_F(PIDToleranceTest, Absolute){ | ||
| + reset(); | ||
| + pid->SetAbsoluteTolerance(tolerance); | ||
| + pid->SetSetpoint(setpoint); | ||
| + pid->Enable(); | ||
| + EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError(); | ||
| + inp.val = setpoint+tolerance/2; | ||
| + Wait(1.0); | ||
| + EXPECT_TRUE(pid->OnTarget())<<"Error was not in tolerance when it should have been. Error was " << pid->GetAvgError(); | ||
| + inp.val = setpoint+10*tolerance; | ||
| + Wait(1.0); | ||
| + EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError(); | ||
| +} | ||
| + | ||
| +TEST_F(PIDToleranceTest, Percent){ | ||
| + reset(); | ||
| + pid->SetPercentTolerance(tolerance); | ||
| + pid->SetSetpoint(setpoint); | ||
| + pid->Enable(); | ||
| + EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError(); | ||
| + inp.val = setpoint+(tolerance)/200*range;//half of percent tolerance away from setpoint | ||
| + Wait(1.0); | ||
| + EXPECT_TRUE(pid->OnTarget())<<"Error was not in tolerance when it should have been. Error was " << pid->GetAvgError(); | ||
| + inp.val = setpoint+(tolerance)/50*range;//double percent tolerance away from setPoint | ||
| + Wait(1.0); | ||
| + EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError(); | ||
| + | ||
| +} |
| @@ -0,0 +1,88 @@ | ||
| +package edu.wpi.first.wpilibj; | ||
| + | ||
| +import java.util.logging.Logger; | ||
| + | ||
| +import org.junit.After; | ||
| +import org.junit.Before; | ||
| +import org.junit.Test; | ||
| +import static org.junit.Assert.assertFalse; | ||
| +import static org.junit.Assert.assertTrue; | ||
| + | ||
| +import edu.wpi.first.wpilibj.test.AbstractComsSetup; | ||
| + | ||
| +public class PIDToleranceTest extends AbstractComsSetup { | ||
| + private static final Logger logger = Logger.getLogger(PIDToleranceTest.class.getName()); | ||
| + private PIDController pid; | ||
| + private final double setPoint = 50.0; | ||
| + private final double tolerance = 10.0; | ||
| + private final double range = 200; | ||
| + private class fakeInput implements PIDSource{ | ||
| + public double val; | ||
| + public fakeInput(){ | ||
| + val = 0; | ||
| + } | ||
| + @Override | ||
| + public PIDSourceType getPIDSourceType() { | ||
| + return PIDSourceType.kDisplacement; | ||
| + } | ||
| + | ||
| + @Override | ||
| + public double pidGet() { | ||
| + return val; | ||
| + } | ||
| + | ||
| + @Override | ||
| + public void setPIDSourceType(PIDSourceType arg0) {} | ||
| + }; | ||
| + private fakeInput inp; | ||
| + private PIDOutput out = new PIDOutput(){ | ||
| + @Override | ||
| + public void pidWrite(double out) { | ||
| + } | ||
| + | ||
| + }; | ||
| + @Override | ||
| + protected Logger getClassLogger() { | ||
| + return logger; | ||
| + } | ||
| + @Before | ||
| + public void setUp() throws Exception{ | ||
| + inp = new fakeInput(); | ||
| + pid = new PIDController(0.05,0.0,0.0,inp,out); | ||
| + pid.setInputRange(-range/2, range/2); | ||
| + } | ||
| + | ||
| + @After | ||
| + public void tearDown() throws Exception{ | ||
| + pid.free(); | ||
| + pid = null; | ||
| + } | ||
| + | ||
| + @Test | ||
| + public void testAbsoluteTolerance(){ | ||
| + pid.setAbsoluteTolerance(tolerance); | ||
| + pid.setSetpoint(setPoint); | ||
| + pid.enable(); | ||
| + Timer.delay(1); | ||
| + assertFalse("Error was in tolerance when it should not have been. Error was "+pid.getAvgError(),pid.onTarget()); | ||
| + inp.val = setPoint+tolerance/2; | ||
| + Timer.delay(1.0); | ||
| + assertTrue("Error was not in tolerance when it should have been. Error was "+pid.getAvgError(),pid.onTarget()); | ||
| + inp.val = setPoint + 10*tolerance; | ||
| + Timer.delay(1.0); | ||
| + assertFalse("Error was in tolerance when it should not have been. Error was "+pid.getAvgError(),pid.onTarget()); | ||
| + } | ||
| + @Test | ||
| + public void testPercentTolerance(){ | ||
| + pid.setPercentTolerance(tolerance); | ||
| + pid.setSetpoint(setPoint); | ||
| + pid.enable(); | ||
| + assertFalse("Error was in tolerance when it should not have been. Error was "+pid.getAvgError(),pid.onTarget()); | ||
| + inp.val = setPoint+(tolerance)/200*range;//half of percent tolerance away from setPoint | ||
| + Timer.delay(1.0); | ||
| + assertTrue("Error was not in tolerance when it should have been. Error was "+pid.getAvgError(),pid.onTarget()); | ||
| + inp.val = setPoint + (tolerance)/50*range;//double percent tolerance away from setPoint | ||
| + Timer.delay(1.0); | ||
| + assertFalse("Error was in tolerance when it should not have been. Error was "+pid.getAvgError(),pid.onTarget()); | ||
| + } | ||
| +} |
Oops, something went wrong.
0 comments on commit
7041cbc