Skip to content

Commit 087bc60

Browse files
authored
Merge pull request #8 from aerostack2/tf_utils_timeout
Read timeout from TfHandler
2 parents 6d99f13 + 47d7420 commit 087bc60

File tree

2 files changed

+1
-11
lines changed

2 files changed

+1
-11
lines changed

include/as2_platform_dji_psdk/as2_platform_dji_psdk.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,6 @@ class DJIMatricePSDKPlatform : public as2::AerialPlatform
9090

9191
// Gimbal
9292
as2::tf::TfHandler tf_handler_;
93-
std::chrono::nanoseconds tf_timeout_;
9493
bool enable_gimbal_;
9594
psdk_interfaces::msg::GimbalRotation gimbal_command_msg_;
9695
rclcpp::Time last_gimbal_command_time_;

src/as2_platform_dji_psdk.cpp

+1-10
Original file line numberDiff line numberDiff line change
@@ -111,15 +111,6 @@ void DJIMatricePSDKPlatform::configureSensors()
111111
sensor_odom_ptr_ = std::make_unique<as2::sensors::Sensor<nav_msgs::msg::Odometry>>("odom", this);
112112
RCLCPP_INFO(this->get_logger(), "DJIMatricePSDKPlatform odometry sensor configured");
113113

114-
// Read tf_timeout_threshold
115-
double tf_timeout_threshold;
116-
this->declare_parameter<double>("tf_timeout_threshold", 0.5);
117-
this->get_parameter("tf_timeout_threshold", tf_timeout_threshold);
118-
tf_timeout_ = std::chrono::duration_cast<std::chrono::nanoseconds>(
119-
std::chrono::duration<double>(tf_timeout_threshold));
120-
RCLCPP_INFO(
121-
this->get_logger(), "DJIMatricePSDKPlatform tf_timeout_threshold: %f", tf_timeout_threshold);
122-
123114
// Initialize the camera streaming service
124115
this->declare_parameter<bool>("enable_camera", false);
125116
bool enable_camera;
@@ -396,7 +387,7 @@ void DJIMatricePSDKPlatform::gimbalControlCallback(
396387
desired_earth_orientation = desired_base_link_orientation;
397388

398389
std::string target_frame = "earth"; // Earth frame
399-
if (!tf_handler_.tryConvert(desired_earth_orientation, target_frame, tf_timeout_)) {
390+
if (!tf_handler_.tryConvert(desired_earth_orientation, target_frame)) {
400391
RCLCPP_ERROR(
401392
this->get_logger(), "Could not transform desired gimbal orientation to earth frame");
402393
return;

0 commit comments

Comments
 (0)