From 94c6aa1dcc34beca441a3490a4ce7712bfd27ea4 Mon Sep 17 00:00:00 2001 From: Alon Faraj Date: Thu, 19 May 2022 11:06:27 +0300 Subject: [PATCH 1/2] fix -Wformat warnings --- ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp b/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp index 5f236dfe7b..3c8a291d2b 100755 --- a/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp +++ b/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp @@ -84,7 +84,7 @@ void AirsimROSWrapper::initialize_airsim() } catch (rpc::rpc_error& e) { std::string msg = e.get_error().as(); - RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, something went wrong.\n%s", msg); + RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, something went wrong.\n%s", msg.c_str()); rclcpp::shutdown(); } } @@ -925,7 +925,7 @@ void AirsimROSWrapper::drone_state_timer_cb() } catch (rpc::rpc_error& e) { std::string msg = e.get_error().as(); - RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API:\n%s", msg); + RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API:\n%s", msg.c_str()); } } @@ -1234,7 +1234,7 @@ void AirsimROSWrapper::img_response_timer_cb() catch (rpc::rpc_error& e) { std::string msg = e.get_error().as(); - RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg); + RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg.c_str()); } } @@ -1253,7 +1253,7 @@ void AirsimROSWrapper::lidar_timer_cb() } catch (rpc::rpc_error& e) { std::string msg = e.get_error().as(); - RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg); + RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg.c_str()); } } From c8241d17d3adaf9d5f38775216c58030ff9300ea Mon Sep 17 00:00:00 2001 From: Alon Faraj Date: Thu, 19 May 2022 11:14:24 +0300 Subject: [PATCH 2/2] fix deprecated rclcpp:::Duration warning --- ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp b/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp index 3c8a291d2b..9f2e83a093 100755 --- a/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp +++ b/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp @@ -682,7 +682,7 @@ sensor_msgs::msg::PointCloud2 AirsimROSWrapper::get_lidar_msg_from_airsim(const if (isENU_) { try { sensor_msgs::msg::PointCloud2 lidar_msg_enu; - auto transformStampedENU = tf_buffer_->lookupTransform(AIRSIM_FRAME_ID, vehicle_name, rclcpp::Time(0), rclcpp::Duration(1)); + auto transformStampedENU = tf_buffer_->lookupTransform(AIRSIM_FRAME_ID, vehicle_name, rclcpp::Time(0), rclcpp::Duration::from_nanoseconds(1)); tf2::doTransform(lidar_msg, lidar_msg_enu, transformStampedENU); lidar_msg_enu.header.stamp = lidar_msg.header.stamp;