Skip to content

Commit e0ec451

Browse files
authored
Replace rclcpp::Rate with rclcpp::WallRate (#3558)
1 parent b22cae3 commit e0ec451

File tree

7 files changed

+8
-8
lines changed

7 files changed

+8
-8
lines changed

moveit_core/robot_state/test/test_aabb.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -160,7 +160,7 @@ TEST_F(TestAABB, TestPR2)
160160
auto pub_aabb =
161161
node->create_publisher<visualization_msgs::msg::Marker>("/visualization_aabb", rmw_qos_profile_default);
162162
auto pub_obb = node->create_publisher<visualization_msgs::msg::Marker>("/visualization_obb", rmw_qos_profile_default);
163-
rclcpp::Rate loop_rate(10);
163+
rclcpp::WallRate loop_rate(10);
164164

165165
// Wait for the publishers to establish connections
166166
sleep(5);

moveit_ros/hybrid_planning/test/test_basic_integration.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -219,7 +219,7 @@ TEST_F(HybridPlanningFixture, ActionCompletion)
219219
auto goal_handle_future = hp_action_client_->async_send_goal(goal_action_request_, send_goal_options_);
220220
});
221221

222-
rclcpp::Rate rate(10);
222+
rclcpp::WallRate rate(10);
223223
while (!action_complete_)
224224
{
225225
executor_.spin_once();
@@ -241,7 +241,7 @@ TEST_F(HybridPlanningFixture, ActionCompletion)
241241
hp_action_client_->async_cancel_all_goals();
242242
});
243243
244-
rclcpp::Rate rate(10);
244+
rclcpp::WallRate rate(10);
245245
while (!action_complete_)
246246
{
247247
executor_.spin_once();

moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,7 @@ void TfPublisher::publishPlanningSceneFrames()
9494
tf2_ros::TransformBroadcaster broadcaster(context_->moveit_cpp_->getNode());
9595
#endif
9696
geometry_msgs::msg::TransformStamped transform;
97-
rclcpp::Rate rate(rate_);
97+
rclcpp::WallRate rate(rate_);
9898

9999
while (keep_running_)
100100
{

moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,6 @@ class TrajectoryMonitorMiddlewareHandle : public TrajectoryMonitor::MiddlewareHa
6666
void sleep() override;
6767

6868
private:
69-
std::unique_ptr<rclcpp::Rate> rate_;
69+
std::unique_ptr<rclcpp::WallRate> rate_;
7070
};
7171
} // namespace planning_scene_monitor

moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -482,7 +482,7 @@ void PlanningSceneMonitor::scenePublishingThread()
482482
moveit_msgs::msg::PlanningScene msg;
483483
bool publish_msg = false;
484484
bool is_full = false;
485-
rclcpp::Rate rate(publish_planning_scene_frequency_);
485+
rclcpp::WallRate rate(publish_planning_scene_frequency_);
486486
{
487487
std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
488488
while (new_scene_update_ == UPDATE_NONE && publish_planning_scene_)

moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor_middleware_handle.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ void planning_scene_monitor::TrajectoryMonitorMiddlewareHandle::setRate(double s
4848
{
4949
if (sampling_frequency > std::numeric_limits<double>::epsilon())
5050
{
51-
rate_ = std::make_unique<rclcpp::Rate>(sampling_frequency);
51+
rate_ = std::make_unique<rclcpp::WallRate>(sampling_frequency);
5252
}
5353
}
5454

moveit_ros/warehouse/src/broadcast.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ int main(int argc, char** argv)
121121
rclcpp::executors::SingleThreadedExecutor executor;
122122
executor.add_node(node);
123123

124-
rclcpp::Rate rate(static_cast<int64_t>(delay) * 1000ms);
124+
rclcpp::WallRate rate(static_cast<int64_t>(delay) * 1000ms);
125125

126126
// publish the scene
127127
if (vm.count("scene"))

0 commit comments

Comments
 (0)