Skip to content

Commit 5b76db4

Browse files
committed
Updated PID logic
Had to adjust pickup and sbridge to get sim and physical pickup agreeing with eachother
1 parent 1054829 commit 5b76db4

File tree

3 files changed

+49
-11
lines changed

3 files changed

+49
-11
lines changed

src/behaviours/src/PID.cpp

Lines changed: 46 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -11,10 +11,13 @@ PID::PID(PIDConfig config)
1111
float PID::PIDOut(float calculatedError, float setPoint)
1212
{
1313

14+
//cout << "ErrorSize: " << Error.size() << endl;
15+
1416
if (Error.size() >= config.errorHistLength)
1517
{
1618
Error.pop_back();
1719
}
20+
1821
Error.insert(Error.begin(), calculatedError); //insert new error into vector for history purposes.
1922

2023
float P = 0; //proportional yaw output
@@ -31,17 +34,48 @@ float PID::PIDOut(float calculatedError, float setPoint)
3134
}
3235

3336
//feed forward
34-
float FF = config.feedForwardMultiplier * setPoint;
37+
//float FF = config.feedForwardMultiplier * setPoint;
38+
float FF = (pow(setPoint, 3) * config.feedForwardMultiplier) + (setPoint * (config.feedForwardMultiplier / 4.6));
39+
40+
if (!config.alwaysIntegral && Error.size() > 1)
41+
{
42+
//check the change of sign to see if the rover overshot its goal
43+
float sign_change = Error[0] / Error[1];
44+
//if the sign has changed between the previous error and the current error
45+
if(sign_change < 0)
46+
{
47+
//reset the integral history and values
48+
integralErrorHistArray.clear();
49+
integralErrorHistArray.resize(config.integralErrorHistoryLength, 0.0);
50+
I = 0;
51+
step = 0;
52+
53+
54+
//Store error zero into temp variable
55+
float error_zero = Error[0];
56+
57+
//clear the error history in order to prevent movement in the incorrect direction because of the sign change
58+
Error.clear();
59+
60+
//put back into vector
61+
Error.push_back(error_zero);
62+
}
63+
}
64+
65+
3566

3667
//error averager
3768
float avgError = 0;
38-
if (Error.size() >= config.errorHistLength) {
39-
for (int i = 0; i < config.errorHistLength; i++) {
69+
if (Error.size() >= config.errorHistLength)
70+
{
71+
for (int i = 0; i < config.errorHistLength; i++)
72+
{
4073
avgError += Error[i];
4174
}
4275
avgError /= config.errorHistLength;//config.errorHistLength;
4376
}
44-
else {
77+
else
78+
{
4579
avgError = calculatedError;
4680
}
4781

@@ -105,7 +139,7 @@ float PID::PIDOut(float calculatedError, float setPoint)
105139
}
106140

107141
//Derivative
108-
if (fabs(P) < config.antiWindup)
142+
if (Error.size() < 4 )//(fabs(P) < config.antiWindup)
109143
{
110144
float avgPrevError = 0;
111145
for (int i = 1; i < Error.size(); i++)
@@ -121,11 +155,17 @@ float PID::PIDOut(float calculatedError, float setPoint)
121155
avgPrevError = Error[0];
122156
}
123157

124-
D = config.Kd * (Error[0] - Error[1]) * hz;
158+
159+
D = config.Kd * ((Error[0]+Error[1])/2 - (Error[2]+Error[3])/2) * hz;
160+
161+
//cout << "PID Error[0]: " << Error[0] << ", Error[1]: " << Error[1] << ", Error[2]: " << Error[2] << ", Error[3]: " << Error[3] << endl;
162+
125163
}
126164

127165
float PIDOut = P + I + D + FF;
128166

167+
//cout << "PID P: " << P << ", I: " << I << ", D: " << D << ", FF: " << FF << endl;
168+
129169
if (PIDOut > config.satUpper) //cap vel command
130170
{
131171
PIDOut = config.satUpper;
@@ -135,7 +175,5 @@ float PID::PIDOut(float calculatedError, float setPoint)
135175
PIDOut = config.satLower;
136176
}
137177

138-
cout << "PID OUTPUT: " << PIDOut << endl;
139-
140178
return PIDOut;
141179
}

src/behaviours/src/PickUpController.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,7 @@ Result PickUpController::DoWork()
227227
// If we don't see any blocks or cubes turn towards the location of the last cube we saw.
228228
// I.E., try to re-aquire the last cube we saw.
229229

230-
float grasp_time_begin = 1.1;
230+
float grasp_time_begin = 1.5;
231231
float raise_time_begin = 2.0;
232232
float lower_gripper_time_begin = 4.0;
233233
float target_reaquire_begin= 4.2;

src/sbridge/src/sbridge.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ void sbridge::cmdHandler(const geometry_msgs::Twist::ConstPtr& message) {
2424
double right = (message->angular.z);
2525

2626
float max_turn_rate = 4.5; //radians per second
27-
float max_linear_velocity = 0.6; // meters per second
27+
float max_linear_velocity = 0.65; // meters per second
2828

2929
float turn = 0;
3030
float forward = 0;
@@ -33,7 +33,7 @@ void sbridge::cmdHandler(const geometry_msgs::Twist::ConstPtr& message) {
3333
float angularVel = (right-left)/2;
3434

3535
turn = angularVel/55;
36-
forward = linearVel/425;
36+
forward = linearVel/390;
3737
if (forward >= 150){
3838
forward -= (abs(turn)/5);
3939
}

0 commit comments

Comments
 (0)