Skip to content

Commit d9b72de

Browse files
Add job for clang build (#239)
1 parent 93955a8 commit d9b72de

File tree

4 files changed

+44
-33
lines changed

4 files changed

+44
-33
lines changed

.github/workflows/build-binary.yml

+11
Original file line numberDiff line numberDiff line change
@@ -25,3 +25,14 @@ jobs:
2525
ros_repo: ${{ matrix.ROS_REPO }}
2626
upstream_workspace: control_toolbox-not-released.${{ matrix.ROS_DISTRO }}.repos
2727
ref_for_scheduled_build: ros2-master
28+
binary_clang:
29+
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master
30+
with:
31+
ros_distro: rolling
32+
ros_repo: testing
33+
upstream_workspace: control_toolbox-not-released.rolling.repos
34+
ref_for_scheduled_build: ros2-master
35+
additional_debs: clang
36+
c_compiler: clang
37+
cxx_compiler: clang++
38+
not_test_build: true

include/control_toolbox/low_pass_filter.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ bool LowPassFilter<T>::configure()
147147
// Initialize storage Vectors
148148
filtered_value = filtered_old_value = old_value = 0;
149149
// TODO(destogl): make the size parameterizable and more intelligent is using complex types
150-
for (size_t i = 0; i < 6; ++i)
150+
for (Eigen::Index i = 0; i < 6; ++i)
151151
{
152152
msg_filtered[i] = msg_filtered_old[i] = msg_old[i] = 0;
153153
}

src/pid_ros.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -221,15 +221,15 @@ std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> PidROS::getPidSt
221221

222222
double PidROS::computeCommand(double error, rclcpp::Duration dt)
223223
{
224-
double cmd_ = pid_.computeCommand(error, dt.nanoseconds());
224+
double cmd_ = pid_.computeCommand(error, static_cast<uint64_t>(dt.nanoseconds()));
225225
publishPIDState(cmd_, error, dt);
226226

227227
return cmd_;
228228
}
229229

230230
double PidROS::computeCommand(double error, double error_dot, rclcpp::Duration dt)
231231
{
232-
double cmd_ = pid_.computeCommand(error, error_dot, dt.nanoseconds());
232+
double cmd_ = pid_.computeCommand(error, error_dot, static_cast<uint64_t>(dt.nanoseconds()));
233233
publishPIDState(cmd_, error, dt);
234234

235235
return cmd_;

test/pid_tests.cpp

+30-30
Original file line numberDiff line numberDiff line change
@@ -80,11 +80,11 @@ TEST(ParameterTest, integrationClampTest)
8080
double cmd = 0.0;
8181

8282
// Test lower limit
83-
cmd = pid.computeCommand(-10.03, 1.0 * 1e9);
83+
cmd = pid.computeCommand(-10.03, static_cast<uint64_t>(1.0 * 1e9));
8484
EXPECT_EQ(-1.0, cmd);
8585

8686
// Test upper limit
87-
cmd = pid.computeCommand(30.0, 1.0 * 1e9);
87+
cmd = pid.computeCommand(30.0, static_cast<uint64_t>(1.0 * 1e9));
8888
EXPECT_EQ(1.0, cmd);
8989
}
9090

@@ -104,13 +104,13 @@ TEST(ParameterTest, integrationClampZeroGainTest)
104104
double cmd = 0.0;
105105
double pe, ie, de;
106106

107-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
107+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
108108
pid.getCurrentPIDErrors(pe, ie, de);
109109
EXPECT_LE(i_min, cmd);
110110
EXPECT_LE(cmd, i_max);
111111
EXPECT_EQ(0.0, cmd);
112112

113-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
113+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
114114
EXPECT_LE(i_min, cmd);
115115
EXPECT_LE(cmd, i_max);
116116
EXPECT_EQ(0.0, cmd);
@@ -129,16 +129,16 @@ TEST(ParameterTest, integrationAntiwindupTest)
129129

130130
double cmd = 0.0;
131131

132-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
132+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
133133
EXPECT_EQ(-1.0, cmd);
134134

135-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
135+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
136136
EXPECT_EQ(-1.0, cmd);
137137

138-
cmd = pid.computeCommand(0.5, 1.0 * 1e9);
138+
cmd = pid.computeCommand(0.5, static_cast<uint64_t>(1.0 * 1e9));
139139
EXPECT_EQ(0.0, cmd);
140140

141-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
141+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
142142
EXPECT_EQ(-1.0, cmd);
143143
}
144144

@@ -155,16 +155,16 @@ TEST(ParameterTest, negativeIntegrationAntiwindupTest)
155155

156156
double cmd = 0.0;
157157

158-
cmd = pid.computeCommand(0.1, 1.0 * 1e9);
158+
cmd = pid.computeCommand(0.1, static_cast<uint64_t>(1.0 * 1e9));
159159
EXPECT_EQ(-0.2, cmd);
160160

161-
cmd = pid.computeCommand(0.1, 1.0 * 1e9);
161+
cmd = pid.computeCommand(0.1, static_cast<uint64_t>(1.0 * 1e9));
162162
EXPECT_EQ(-0.2, cmd);
163163

164-
cmd = pid.computeCommand(-0.05, 1.0 * 1e9);
164+
cmd = pid.computeCommand(-0.05, static_cast<uint64_t>(1.0 * 1e9));
165165
EXPECT_EQ(-0.075, cmd);
166166

167-
cmd = pid.computeCommand(0.1, 1.0 * 1e9);
167+
cmd = pid.computeCommand(0.1, static_cast<uint64_t>(1.0 * 1e9));
168168
EXPECT_EQ(-0.2, cmd);
169169
}
170170

@@ -223,7 +223,7 @@ TEST(ParameterTest, gainSettingCopyPIDTest)
223223

224224
// Send update command to populate errors -------------------------------------------------
225225
pid1.setCurrentCmd(10);
226-
(void) pid1.computeCommand(20, 1.0 * 1e9);
226+
(void) pid1.computeCommand(20, static_cast<uint64_t>(1.0 * 1e9));
227227

228228
// Test copy constructor -------------------------------------------------
229229
Pid pid2(pid1);
@@ -291,22 +291,22 @@ TEST(CommandTest, proportionalOnlyTest)
291291
double cmd = 0.0;
292292

293293
// If initial error = 0, p-gain = 1, dt = 1
294-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
294+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
295295
// Then expect command = error
296296
EXPECT_EQ(-0.5, cmd);
297297

298298
// If call again
299-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
299+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
300300
// Then expect the same as before
301301
EXPECT_EQ(-0.5, cmd);
302302

303303
// If call again doubling the error
304-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
304+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
305305
// Then expect the command doubled
306306
EXPECT_EQ(-1.0, cmd);
307307

308308
// If call with positive error
309-
cmd = pid.computeCommand(0.5, 1.0 * 1e9);
309+
cmd = pid.computeCommand(0.5, static_cast<uint64_t>(1.0 * 1e9));
310310
// Then expect always command = error
311311
EXPECT_EQ(0.5, cmd);
312312
}
@@ -323,26 +323,26 @@ TEST(CommandTest, integralOnlyTest)
323323
double cmd = 0.0;
324324

325325
// If initial error = 0, i-gain = 1, dt = 1
326-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
326+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
327327
// Then expect command = error
328328
EXPECT_EQ(-0.5, cmd);
329329

330330
// If call again with same arguments
331-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
331+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
332332
// Then expect the integral part to double the command
333333
EXPECT_EQ(-1.0, cmd);
334334

335335
// Call again with no error
336-
cmd = pid.computeCommand(0.0, 1.0 * 1e9);
336+
cmd = pid.computeCommand(0.0, static_cast<uint64_t>(1.0 * 1e9));
337337
// Expect the integral part to keep the previous command because it ensures error = 0
338338
EXPECT_EQ(-1.0, cmd);
339339

340340
// Double check that the integral contribution keep the previous command
341-
cmd = pid.computeCommand(0.0, 1.0 * 1e9);
341+
cmd = pid.computeCommand(0.0, static_cast<uint64_t>(1.0 * 1e9));
342342
EXPECT_EQ(-1.0, cmd);
343343

344344
// Finally call again with positive error to see if the command changes in the opposite direction
345-
cmd = pid.computeCommand(1.0, 1.0 * 1e9);
345+
cmd = pid.computeCommand(1.0, static_cast<uint64_t>(1.0 * 1e9));
346346
// Expect that the command is cleared since error = -1 * previous command, i-gain = 1, dt = 1
347347
EXPECT_EQ(0.0, cmd);
348348
}
@@ -359,27 +359,27 @@ TEST(CommandTest, derivativeOnlyTest)
359359
double cmd = 0.0;
360360

361361
// If initial error = 0, d-gain = 1, dt = 1
362-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
362+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
363363
// Then expect command = error
364364
EXPECT_EQ(-0.5, cmd);
365365

366366
// If call again with same error
367-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
367+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
368368
// Then expect command = 0 due to no variation on error
369369
EXPECT_EQ(0.0, cmd);
370370

371371
// If call again with same error and smaller control period
372-
cmd = pid.computeCommand(-0.5, 0.1 * 1e9);
372+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(0.1 * 1e9));
373373
// Then expect command = 0 again
374374
EXPECT_EQ(0.0, cmd);
375375

376376
// If the error increases, with dt = 1
377-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
377+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
378378
// Then expect the command = change in dt
379379
EXPECT_EQ(-0.5, cmd);
380380

381381
// If error decreases, with dt = 1
382-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
382+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
383383
// Then expect always the command = change in dt (note the sign flip)
384384
EXPECT_EQ(0.5, cmd);
385385
}
@@ -396,17 +396,17 @@ TEST(CommandTest, completePIDTest)
396396

397397
// All contributions are tested, here few tests check that they sum up correctly
398398
// If initial error = 0, all gains = 1, dt = 1
399-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
399+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
400400
// Then expect command = 3x error
401401
EXPECT_EQ(-1.5, cmd);
402402

403403
// If call again with same arguments, no error change, but integration do its part
404-
cmd = pid.computeCommand(-0.5, 1.0 * 1e9);
404+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
405405
// Then expect command = 3x error again
406406
EXPECT_EQ(-1.5, cmd);
407407

408408
// If call again increasing the error
409-
cmd = pid.computeCommand(-1.0, 1.0 * 1e9);
409+
cmd = pid.computeCommand(-1.0, static_cast<uint64_t>(1.0 * 1e9));
410410
// Then expect command equals to p = -1, i = -2.0 (i.e. - 0.5 - 0.5 - 1.0), d = -0.5
411411
EXPECT_EQ(-3.5, cmd);
412412
}

0 commit comments

Comments
 (0)