Skip to content

Commit c07a68b

Browse files
committed
set the controller's update rate if the node's update_rate parameter is undefined, and make precommit happy
1 parent b3262b5 commit c07a68b

File tree

6 files changed

+13
-5
lines changed

6 files changed

+13
-5
lines changed

controller_interface/src/controller_interface.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,14 @@ const rclcpp_lifecycle::State & ControllerInterface::configure()
6565
break;
6666
}
6767

68-
update_rate_ = node_->get_parameter("update_rate").as_int();
68+
if (node_->has_parameter("update_rate"))
69+
{
70+
update_rate_ = node_->get_parameter("update_rate").as_int();
71+
}
72+
else
73+
{
74+
update_rate_ = 0;
75+
}
6976
}
7077
return lifecycle_state_;
7178
}

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,7 @@ class ControllerManager : public rclcpp::Node
144144
// the executor (see issue #260).
145145
// rclcpp::CallbackGroup::SharedPtr deterministic_callback_group_;
146146

147-
//Per controller update rate support
147+
// Per controller update rate support
148148
unsigned int get_update_rate() const;
149149
void configure();
150150

@@ -223,7 +223,7 @@ class ControllerManager : public rclcpp::Node
223223
const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
224224
std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);
225225

226-
//Per controller update rate support
226+
// Per controller update rate support
227227
unsigned int update_loop_counter_ = 0;
228228
unsigned int update_rate_ = 100;
229229

4.85 KB
Binary file not shown.

controller_manager/test/controller_manager_test_common.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <memory>
2323
#include <string>
2424
#include <thread>
25+
#include <utility>
2526
#include <vector>
2627

2728
#include "controller_interface/controller_interface.hpp"

controller_manager/test/test_controller_manager.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -171,7 +171,7 @@ TEST_F(TestControllerManager, per_controller_update_rate)
171171
controller_interface::return_type::OK,
172172
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
173173
EXPECT_GE(test_controller->internal_counter, 1u);
174-
EXPECT_EQ(test_controller->get_update_rate(), 4);
174+
EXPECT_EQ(test_controller->get_update_rate(), 4u);
175175
}
176176
/* WIP
177177
TEST_F(TestControllerManager, inactive_controller_does_not_get_updated)

controller_manager/test/test_load_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -589,5 +589,5 @@ TEST_F(TestLoadController, can_set_and_get_non_default_update_rate)
589589
cm_->configure_controller("test_controller_01");
590590
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if->get_state().id());
591591

592-
EXPECT_EQ(1337, controller_if->get_update_rate());
592+
EXPECT_EQ(1337u, controller_if->get_update_rate());
593593
}

0 commit comments

Comments
 (0)