Talon PID on swerve - Crossing 0/360 boundary

Hey there!
We are building a rotational module and using the CTRE encoder for position (1:1), and controlling the motor with a Talon SRX, using cpp as the language.

It works and goes to the set angle/position from where it’s at, but it’s not an ideal solution.

If the mechanism is at 350 degrees, and the new set point is 10 degrees, it rotates all the way back 340 degrees vs the shorter path of 20. We have written code that solves this for other systems, but it seems like the Talon, already running a PID loops, and interfacing with the encoder, may already handle this somewhere in the firmware. One of the added complexities here is that the Talon really returns total number of turns/degrees, so the likely fix is to tell it to turn to 370 degrees, and add an accumulator of turns/degrees in the RoboRio code.

Just wondering if we are missing something silly, or there’s a more elegant way that the Talon already supports.

The reference manual mentions that you can use the ctre encoders in 2 modes - absolute and relative. Maybe you need the encoder in relative mode?

We are actually in relative mode:

SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative)

I think in the case of the talon and CTRE encoder, Absolute is really referencing the PWM encoder sensor, and Relative is seems to reference the quadrature/incremental sensor in the encoder package. We are reading the PWN and using that to seed the relative encoder at startup and then switching to reading the “relative” encoder during operation for lower latency of readings.

We had (and still have, sometimes) this problem for a long time. We aren’t using the mag encoders though, just some other generic quadrature ones.

There’s a method called

steerMotor.configEncoderCodesPerRev

which translates the native units of encoder counts etc to revolutions. So you can get and set the target speed in RPM instead of counts per 100ms, or fractions of revolutions instead of encoder counts. But it’s unclear if that actually does the 0-360 logic for you. I would think not, since if you were using it to spin your drivetrain wheels in a tank drive, then -0.1 rotation is not the same as +0.9. Maybe you can look more into this one and see if it’s usable? I am not sure, since the codes per rev on the mag encoder is already known by the Talon (4096?).

Right now I have it set to basically:

  1. track the number of complete revolutions so far (call it n here)
  2. when a new angle is assigned, calculate three setpoints that are equivalent to that angle: the one on the (n-1)th rotation, the one on the nth rotation, and the one on the (n+1)th rotation.
  3. Find the closest one (just find the minimum difference)
  4. Go there.

It works maybe 30-40% of the time and is really, really not elegant. If you want to add logic that, for example

You’d need six possible setpoints. It gets ugly really quickly. I suppose that was what you were suggesting in the original post, but I wouldn’t recommend it and I hope there’s a more elegant solution out there that I am missing.

We use the same mechanical setup. I believe (I’m not the programmer) upon startup we read the absolute to know where the wheel is, do some offset math so the wheel doesn’t have to move to find zero then use the incremental to do the control part. We do this to avoid the problem you’re having. We also have a zero calibrate routine that is done in the pits in case a belt jumps a tooth which requires the wheels to be manually aligned then the code is told that the current wheel position is zero.

My vote is to do position control with the incremental.

How are you calculating the closest setpoint? As in 350->370 instead of 350->10.

Starting to get over my head here (remember, not the programmer). You can look at the code, it’s on github.

I’ll try to get a better answer.

Thanks! I’ll look through it over my break.

I actually emailed Omar about this last night. The problem is that the closed loop position control on the talon uses the encoder position with overflow. In the case of drive train encoder or an elevator this is valid and makes sense. I pleaded our case to Omar at worlds that there should be an option to use close loop position control without overflow. I’m not sure when we can expect this functionality but he agreed that the request was reasonable and a common use case. Someone can correct me if I’m wrong but I believe Mike told me that the option exists for Analog encoders already.

One other thing I will mention is that we kept the 2 optimization problems separate.

The first being that when commanding the Talon setpoint you should never have to rotate more than 180 degrees to get to the setpoint.

The second being that in the specific case of a swerve drive module you never need to rotate more than 90 degrees to get to the setpoint but you may have to reverse the wheel direction.

The work around we used for our swerve drive is the following.


int CTREMagEncoder::ConvertAngleToSetpoint(Rotation2D targetAngle) {
	Rotation2D angle = targetAngle.rotateBy(m_offset);
	
	int ticks = ConvertAngleToEncoderTicks(angle); // 0 - 4096
	
	int encoderTicks = GetEncoderTicks(true);
	ticks += (encoderTicks/4096)*4096; //Add ticks equivalent to full rotations on encoder.
	
	int error = encoderTicks - ticks;

	// Ensure the movement is <= 180 deg (2048 encoder ticks)
	if (error < -2048) {
		ticks -= 4096;
	}
	else if (error > 2048) {
		ticks += 4096;
	}

	return ticks;
}

You can find the full source of our off season swerve (less tested but cleaner) and our 2017 competition swerve at the following links.

2017 Competition: https://github.com/Frc2481/frc-2017/blob/master/r2017/src/Components/SwerveModule.cpp#L196
Offseason: https://github.com/Frc2481/frc-2017-swerve/blob/master/src/CTREMagEncoder.cpp#L59

Ahh I remember running into this problem, take a look at this code https://github.com/Robostangs/SideStep