Skip to content

Commit

Permalink
Merge pull request #8 from aerostack2/tf_utils_timeout
Browse files Browse the repository at this point in the history
Read timeout from TfHandler
  • Loading branch information
pariaspe authored Dec 4, 2024
2 parents 6d99f13 + 47d7420 commit 087bc60
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 11 deletions.
1 change: 0 additions & 1 deletion include/as2_platform_dji_psdk/as2_platform_dji_psdk.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,6 @@ class DJIMatricePSDKPlatform : public as2::AerialPlatform

// Gimbal
as2::tf::TfHandler tf_handler_;
std::chrono::nanoseconds tf_timeout_;
bool enable_gimbal_;
psdk_interfaces::msg::GimbalRotation gimbal_command_msg_;
rclcpp::Time last_gimbal_command_time_;
Expand Down
11 changes: 1 addition & 10 deletions src/as2_platform_dji_psdk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,15 +111,6 @@ void DJIMatricePSDKPlatform::configureSensors()
sensor_odom_ptr_ = std::make_unique<as2::sensors::Sensor<nav_msgs::msg::Odometry>>("odom", this);
RCLCPP_INFO(this->get_logger(), "DJIMatricePSDKPlatform odometry sensor configured");

// Read tf_timeout_threshold
double tf_timeout_threshold;
this->declare_parameter<double>("tf_timeout_threshold", 0.5);
this->get_parameter("tf_timeout_threshold", tf_timeout_threshold);
tf_timeout_ = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double>(tf_timeout_threshold));
RCLCPP_INFO(
this->get_logger(), "DJIMatricePSDKPlatform tf_timeout_threshold: %f", tf_timeout_threshold);

// Initialize the camera streaming service
this->declare_parameter<bool>("enable_camera", false);
bool enable_camera;
Expand Down Expand Up @@ -396,7 +387,7 @@ void DJIMatricePSDKPlatform::gimbalControlCallback(
desired_earth_orientation = desired_base_link_orientation;

std::string target_frame = "earth"; // Earth frame
if (!tf_handler_.tryConvert(desired_earth_orientation, target_frame, tf_timeout_)) {
if (!tf_handler_.tryConvert(desired_earth_orientation, target_frame)) {
RCLCPP_ERROR(
this->get_logger(), "Could not transform desired gimbal orientation to earth frame");
return;
Expand Down

0 comments on commit 087bc60

Please sign in to comment.