Skip to content

Commit b7bceea

Browse files
nbbrooksmosfet80
authored andcommitted
Fix deprecations in image_common and tf2_ros (moveit#3567)
* Fix image_common NodeT deprecation warnings from ros-perception/image_common#352 - migrate to NodeInterfaces * Fix image_common rmw_qos_profile_t deprecation warnings from ros-perception/image_common#364 - migrate to rclcpp::QoS * Fix rviz update float deprecation warnings from ros2/rviz#1533 - migrate to std::chrono::duration * Fix geometry2 tf2_ros .h deprecation warnings from ros2/geometry2#805 - migrate Kilted and Rolling to .hpp * Fix geometry2 tf2_ros NodeT deprecation warnings from ros2/geometry2#714 - migrate to NodeInterfaces * Fix rclcpp spin_some deprecation warnings from ros2/rclcpp#2848 - migrate to SingleThreadedExecutor --------- Co-authored-by: Andrea <realeandrea@yahoo.it>
1 parent 89a7833 commit b7bceea

File tree

46 files changed

+482
-41
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

46 files changed

+482
-41
lines changed

moveit_kinematics/test/test_kinematics_plugin.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include <memory>
4040
#include <functional>
4141
#include <pluginlib/class_loader.hpp>
42+
#include <rclcpp/executors/single_threaded_executor.hpp>
4243
#include <rclcpp/rclcpp.hpp>
4344
#include <tf2_eigen/tf2_eigen.hpp>
4445

@@ -403,7 +404,9 @@ TEST_F(KinematicsTest, randomWalkIK)
403404
auto pub = node_->create_publisher<moveit_msgs::msg::DisplayTrajectory>("display_random_walk", 1);
404405
traj.getRobotTrajectoryMsg(msg.trajectory[0]);
405406
pub->publish(msg);
406-
rclcpp::spin_some(node_);
407+
rclcpp::executors::SingleThreadedExecutor executor;
408+
executor.add_node(node_);
409+
executor.spin_some();
407410
}
408411
}
409412

moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040
#pragma once
4141

4242
#include <rclcpp/rclcpp.hpp>
43+
#include <rclcpp/version.h>
4344
#include <rclcpp_action/rclcpp_action.hpp>
4445

4546
#include <pluginlib/class_loader.hpp>
@@ -58,8 +59,15 @@
5859
#include <moveit/local_planner/local_constraint_solver_interface.hpp>
5960
#include <moveit/local_planner/trajectory_operator_interface.hpp>
6061

62+
// For Rolling, Kilted, and newer
63+
#if RCLCPP_VERSION_GTE(29, 6, 0)
64+
#include <tf2_ros/buffer.hpp>
65+
#include <tf2_ros/transform_listener.hpp>
66+
// For Jazzy and older
67+
#else
6168
#include <tf2_ros/buffer.h>
6269
#include <tf2_ros/transform_listener.h>
70+
#endif
6371

6472
// Forward declaration of parameter class allows users to implement custom parameters
6573
namespace local_planner_parameters

moveit_ros/hybrid_planning/test/test_basic_integration.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,8 +41,16 @@
4141
#include <moveit/planning_scene_monitor/planning_scene_monitor.hpp>
4242
#include <moveit/robot_state/conversions.hpp>
4343
#include <rclcpp/rclcpp.hpp>
44+
#include <rclcpp/version.h>
4445
#include <rclcpp_action/rclcpp_action.hpp>
46+
47+
// For Rolling, Kilted, and newer
48+
#if RCLCPP_VERSION_GTE(29, 6, 0)
4549
#include <tf2_ros/buffer.hpp>
50+
// For Jazzy and older
51+
#else
52+
#include <tf2_ros/buffer.h>
53+
#endif
4654

4755
#include <moveit_msgs/action/hybrid_planner.hpp>
4856
#include <moveit_msgs/msg/display_robot_state.hpp>

moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,10 +35,19 @@
3535
/* Author: Jonas Tietz */
3636

3737
#include "tf_publisher_capability.hpp"
38+
39+
#include <rclcpp/version.h>
40+
3841
#include <moveit/moveit_cpp/moveit_cpp.hpp>
3942
#include <moveit/utils/message_checks.hpp>
4043
#include <moveit/move_group/capability_names.hpp>
44+
// For Rolling, Kilted, and newer
45+
#if RCLCPP_VERSION_GTE(29, 6, 0)
46+
#include <tf2_ros/transform_broadcaster.hpp>
47+
// For Jazzy and older
48+
#else
4149
#include <tf2_ros/transform_broadcaster.h>
50+
#endif
4251
#include <tf2_eigen/tf2_eigen.hpp>
4352
#include <moveit/robot_state/robot_state.hpp>
4453
#include <moveit/robot_state/attached_body.hpp>
@@ -76,7 +85,14 @@ void publishSubframes(tf2_ros::TransformBroadcaster& broadcaster, const moveit::
7685

7786
void TfPublisher::publishPlanningSceneFrames()
7887
{
88+
// For Rolling, L-turtle, and newer
89+
#if RCLCPP_VERSION_GTE(30, 0, 0)
90+
tf2_ros::TransformBroadcaster broadcaster(tf2_ros::TransformBroadcaster::RequiredInterfaces{
91+
context_->moveit_cpp_->getNode()->get_node_parameters_interface(),
92+
context_->moveit_cpp_->getNode()->get_node_topics_interface() });
93+
#else
7994
tf2_ros::TransformBroadcaster broadcaster(context_->moveit_cpp_->getNode());
95+
#endif
8096
geometry_msgs::msg::TransformStamped transform;
8197
rclcpp::Rate rate(rate_);
8298

moveit_ros/move_group/src/move_group.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,19 @@
3434

3535
/* Author: Ioan Sucan */
3636

37+
#include <rclcpp/version.h>
38+
3739
#include <moveit/moveit_cpp/moveit_cpp.hpp>
3840
#include <moveit/planning_scene_monitor/planning_scene_monitor.hpp>
41+
// For Rolling, L-turtle, and newer
42+
43+
// For Rolling, Kilted, and newer
44+
#if RCLCPP_VERSION_GTE(29, 6, 0)
45+
#include <tf2_ros/transform_listener.hpp>
46+
// For Jazzy and older
47+
#else
3948
#include <tf2_ros/transform_listener.h>
49+
#endif
4050
#include <moveit/move_group/move_group_capability.hpp>
4151
#include <moveit/trajectory_execution_manager/trajectory_execution_manager.hpp>
4252
#include <boost/tokenizer.hpp>

moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,8 +44,15 @@
4444
#include <moveit_servo/utils/common.hpp>
4545
#include <mutex>
4646
#include <rclcpp/rclcpp.hpp>
47+
#include <rclcpp/version.h>
4748
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
49+
// For Rolling, Kilted, and newer
50+
#if RCLCPP_VERSION_GTE(29, 6, 0)
51+
#include <tf2_ros/transform_listener.hpp>
52+
// For Jazzy and older
53+
#else
4854
#include <tf2_ros/transform_listener.h>
55+
#endif
4956
#include <moveit/utils/logger.hpp>
5057

5158
using namespace moveit_servo;

moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,15 @@
4343
#include <moveit_servo/servo.hpp>
4444
#include <moveit_servo/utils/common.hpp>
4545
#include <rclcpp/rclcpp.hpp>
46+
#include <rclcpp/version.h>
4647
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
48+
// For Rolling, Kilted, and newer
49+
#if RCLCPP_VERSION_GTE(29, 6, 0)
50+
#include <tf2_ros/transform_listener.hpp>
51+
// For Jazzy and older
52+
#else
4753
#include <tf2_ros/transform_listener.h>
54+
#endif
4855
#include <moveit/utils/logger.hpp>
4956

5057
using namespace moveit_servo;

moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@
4242
#include <control_msgs/msg/joint_jog.hpp>
4343
#include <geometry_msgs/msg/twist_stamped.hpp>
4444
#include <moveit_msgs/srv/servo_command_type.hpp>
45+
#include <rclcpp/executors/single_threaded_executor.hpp>
4546
#include <rclcpp/rclcpp.hpp>
4647
#include <signal.h>
4748
#include <stdio.h>
@@ -188,9 +189,11 @@ int main(int argc, char** argv)
188189

189190
void KeyboardServo::spin()
190191
{
192+
rclcpp::executors::SingleThreadedExecutor executor;
193+
executor.add_node(nh_);
191194
while (rclcpp::ok())
192195
{
193-
rclcpp::spin_some(nh_);
196+
executor.spin_some();
194197
}
195198
}
196199

moveit_ros/moveit_servo/include/moveit_servo/servo.hpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,9 @@
4141

4242
#pragma once
4343

44+
#include <rclcpp/logger.hpp>
45+
#include <rclcpp/version.h>
46+
4447
#include <moveit_servo/collision_monitor.hpp>
4548
#include <moveit_servo/moveit_servo_lib_parameters.hpp>
4649
#include <moveit_servo/utils/command.hpp>
@@ -51,9 +54,14 @@
5154
#include <pluginlib/class_loader.hpp>
5255
#include <sensor_msgs/msg/joint_state.hpp>
5356
#include <tf2_eigen/tf2_eigen.hpp>
57+
// For Rolling, Kilted, and newer
58+
#if RCLCPP_VERSION_GTE(29, 6, 0)
59+
#include <tf2_ros/transform_listener.hpp>
60+
// For Jazzy and older
61+
#else
5462
#include <tf2_ros/transform_listener.h>
63+
#endif
5564
#include <variant>
56-
#include <rclcpp/logger.hpp>
5765
#include <queue>
5866

5967
namespace moveit_servo

moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,14 @@
4242
#include <moveit_msgs/srv/save_map.hpp>
4343

4444
#include <rclcpp/rclcpp.hpp>
45+
#include <rclcpp/version.h>
46+
// For Rolling, Kilted, and newer
47+
#if RCLCPP_VERSION_GTE(29, 6, 0)
48+
#include <tf2_ros/buffer.hpp>
49+
// For Jazzy and older
50+
#else
4551
#include <tf2_ros/buffer.h>
52+
#endif
4653

4754
#include <functional>
4855
#include <memory>

0 commit comments

Comments
 (0)