forked from Yet-Another-Software-Suite/YAGSL-Example
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathPigeonSwerve.java
More file actions
147 lines (131 loc) · 3.32 KB
/
PigeonSwerve.java
File metadata and controls
147 lines (131 loc) · 3.32 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
package swervelib.imu;
import static edu.wpi.first.units.Units.DegreesPerSecond;
import com.ctre.phoenix.sensors.WPI_PigeonIMU;
import edu.wpi.first.math.geometry.Quaternion;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.units.measure.MutAngularVelocity;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import java.util.Optional;
/**
* SwerveIMU interface for the {@link WPI_PigeonIMU}.
*/
public class PigeonSwerve extends SwerveIMU
{
/**
* {@link WPI_PigeonIMU} IMU device.
*/
private final WPI_PigeonIMU imu;
/**
* Mutable {@link MutAngularVelocity} for readings.
*/
private final MutAngularVelocity yawVel = new MutAngularVelocity(0, 0, DegreesPerSecond);
/**
* Offset for the {@link WPI_PigeonIMU}.
*/
private Rotation3d offset = new Rotation3d();
/**
* Inversion for the gyro
*/
private boolean invertedIMU = false;
/**
* Generate the SwerveIMU for {@link WPI_PigeonIMU}.
*
* @param canid CAN ID for the {@link WPI_PigeonIMU}, does not support CANBus.
*/
public PigeonSwerve(int canid)
{
imu = new WPI_PigeonIMU(canid);
offset = new Rotation3d();
SmartDashboard.putData(imu);
}
@Override
public void close() {
imu.close();
}
/**
* Reset IMU to factory default.
*/
@Override
public void factoryDefault()
{
imu.configFactoryDefault();
}
/**
* Clear sticky faults on IMU.
*/
@Override
public void clearStickyFaults()
{
imu.clearStickyFaults();
}
/**
* Set the gyro offset.
*
* @param offset gyro offset as a {@link Rotation3d}.
*/
public void setOffset(Rotation3d offset)
{
this.offset = offset;
}
/**
* Set the gyro to invert its default direction
*
* @param invertIMU invert gyro direction
*/
public void setInverted(boolean invertIMU)
{
invertedIMU = invertIMU;
}
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
* @return {@link Rotation3d} from the IMU.
*/
@Override
public Rotation3d getRawRotation3d()
{
double[] wxyz = new double[4];
imu.get6dQuaternion(wxyz);
Rotation3d reading = new Rotation3d(new Quaternion(wxyz[0], wxyz[1], wxyz[2], wxyz[3]));
return invertedIMU ? reading.unaryMinus() : reading;
}
/**
* Fetch the {@link Rotation3d} from the IMU. Robot relative.
*
* @return {@link Rotation3d} from the IMU.
*/
@Override
public Rotation3d getRotation3d()
{
return getRawRotation3d().minus(offset);
}
/**
* Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
* empty.
*
* @return {@link Translation3d} of the acceleration as an {@link Optional}.
*/
@Override
public Optional<Translation3d> getAccel()
{
short[] initial = new short[3];
imu.getBiasedAccelerometer(initial);
return Optional.of(new Translation3d(initial[0], initial[1], initial[2]).times(9.81 / 16384.0));
}
@Override
public MutAngularVelocity getYawAngularVelocity()
{
return yawVel.mut_setMagnitude(imu.getRate());
}
/**
* Get the instantiated {@link WPI_PigeonIMU} IMU object.
*
* @return IMU object.
*/
@Override
public Object getIMU()
{
return imu;
}
}