[examples] Update Field2d position in periodic() (#2928)

This ensures that the robot position will be updated in dashboards like Glass when running on real hardware.
This commit is contained in:
Prateek Machiraju
2020-12-10 23:36:20 -05:00
committed by GitHub
parent f78d1d4340
commit 65219f3093
7 changed files with 18 additions and 9 deletions

View File

@@ -138,7 +138,10 @@ public class Drivetrain {
m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPositionMeters());
m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocityMetersPerSecond());
m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
}
public void periodic() {
updateOdometry();
m_fieldSim.setRobotPose(m_odometry.getPoseMeters());
}
}

View File

@@ -43,6 +43,11 @@ public class Robot extends TimedRobot {
);
}
@Override
public void robotPeriodic() {
m_drive.periodic();
}
@Override
public void autonomousInit() {
m_timer.reset();
@@ -56,7 +61,6 @@ public class Robot extends TimedRobot {
Trajectory.State reference = m_trajectory.sample(elapsed);
ChassisSpeeds speeds = m_ramsete.calculate(m_drive.getPose(), reference);
m_drive.drive(speeds.vxMetersPerSecond, speeds.omegaRadiansPerSecond);
m_drive.updateOdometry();
}
@Override

View File

@@ -100,6 +100,7 @@ public class DriveSubsystem extends SubsystemBase {
// the Field2d class lets us visualize our robot in the simulation GUI.
m_fieldSim = new Field2d();
SmartDashboard.putData("Field", m_fieldSim);
}
}
@@ -108,6 +109,7 @@ public class DriveSubsystem extends SubsystemBase {
// Update the odometry in the periodic block
m_odometry.update(Rotation2d.fromDegrees(getHeading()), m_leftEncoder.getDistance(),
m_rightEncoder.getDistance());
m_fieldSim.setRobotPose(getPose());
}
@Override
@@ -125,9 +127,6 @@ public class DriveSubsystem extends SubsystemBase {
m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPositionMeters());
m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocityMetersPerSecond());
m_gyroAngleSim.set(-m_drivetrainSimulator.getHeading().getDegrees());
m_fieldSim.setRobotPose(getPose());
SmartDashboard.putData("Field", m_fieldSim);
}
/**