Skip to content

Commit d893231

Browse files
Remove unused variables and correctly override test class method (#1918)
1 parent dbdbc9d commit d893231

File tree

2 files changed

+1
-5
lines changed

2 files changed

+1
-5
lines changed

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -583,8 +583,6 @@ TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_tru
583583
size_t n_joints = joint_names_.size();
584584

585585
// send msg
586-
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
587-
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
588586
// *INDENT-OFF*
589587
std::vector<std::vector<double>> points{
590588
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
@@ -675,8 +673,6 @@ TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_fal
675673
size_t n_joints = joint_names_.size();
676674

677675
// send msg
678-
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
679-
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
680676
// *INDENT-OFF*
681677
std::vector<std::vector<double>> points{
682678
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -232,7 +232,7 @@ class TrajectoryControllerTest : public ::testing::Test
232232
public:
233233
static void SetUpTestCase() { rclcpp::init(0, nullptr); }
234234

235-
virtual void SetUp()
235+
void SetUp() override
236236
{
237237
controller_name_ = "test_joint_trajectory_controller";
238238

0 commit comments

Comments
 (0)