Skip to content

Commit caa1318

Browse files
authored
Merge pull request #4532 from alonfaraj/fix-ros2-warnings
Fix ros2 compilation warnings
2 parents 7bac045 + c8241d1 commit caa1318

File tree

1 file changed

+5
-5
lines changed

1 file changed

+5
-5
lines changed

ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ void AirsimROSWrapper::initialize_airsim()
8484
}
8585
catch (rpc::rpc_error& e) {
8686
std::string msg = e.get_error().as<std::string>();
87-
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, something went wrong.\n%s", msg);
87+
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, something went wrong.\n%s", msg.c_str());
8888
rclcpp::shutdown();
8989
}
9090
}
@@ -682,7 +682,7 @@ sensor_msgs::msg::PointCloud2 AirsimROSWrapper::get_lidar_msg_from_airsim(const
682682
if (isENU_) {
683683
try {
684684
sensor_msgs::msg::PointCloud2 lidar_msg_enu;
685-
auto transformStampedENU = tf_buffer_->lookupTransform(AIRSIM_FRAME_ID, vehicle_name, rclcpp::Time(0), rclcpp::Duration(1));
685+
auto transformStampedENU = tf_buffer_->lookupTransform(AIRSIM_FRAME_ID, vehicle_name, rclcpp::Time(0), rclcpp::Duration::from_nanoseconds(1));
686686
tf2::doTransform(lidar_msg, lidar_msg_enu, transformStampedENU);
687687

688688
lidar_msg_enu.header.stamp = lidar_msg.header.stamp;
@@ -925,7 +925,7 @@ void AirsimROSWrapper::drone_state_timer_cb()
925925
}
926926
catch (rpc::rpc_error& e) {
927927
std::string msg = e.get_error().as<std::string>();
928-
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API:\n%s", msg);
928+
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API:\n%s", msg.c_str());
929929
}
930930
}
931931

@@ -1234,7 +1234,7 @@ void AirsimROSWrapper::img_response_timer_cb()
12341234

12351235
catch (rpc::rpc_error& e) {
12361236
std::string msg = e.get_error().as<std::string>();
1237-
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg);
1237+
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg.c_str());
12381238
}
12391239
}
12401240

@@ -1253,7 +1253,7 @@ void AirsimROSWrapper::lidar_timer_cb()
12531253
}
12541254
catch (rpc::rpc_error& e) {
12551255
std::string msg = e.get_error().as<std::string>();
1256-
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg);
1256+
RCLCPP_ERROR(nh_->get_logger(), "Exception raised by the API, didn't get image response.\n%s", msg.c_str());
12571257
}
12581258
}
12591259

0 commit comments

Comments
 (0)