@@ -111,15 +111,6 @@ void DJIMatricePSDKPlatform::configureSensors()
111
111
sensor_odom_ptr_ = std::make_unique<as2::sensors::Sensor<nav_msgs::msg::Odometry>>(" odom" , this );
112
112
RCLCPP_INFO (this ->get_logger (), " DJIMatricePSDKPlatform odometry sensor configured" );
113
113
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
-
123
114
// Initialize the camera streaming service
124
115
this ->declare_parameter <bool >(" enable_camera" , false );
125
116
bool enable_camera;
@@ -396,7 +387,7 @@ void DJIMatricePSDKPlatform::gimbalControlCallback(
396
387
desired_earth_orientation = desired_base_link_orientation;
397
388
398
389
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)) {
400
391
RCLCPP_ERROR (
401
392
this ->get_logger (), " Could not transform desired gimbal orientation to earth frame" );
402
393
return ;
0 commit comments