Transform Broadcaster - Weber-State-UAV-Program/Documentation-2024-2025 GitHub Wiki
The transform broadcaster node is responsible for publishing all relevant transform data to the /tf
topic. The precision landing node uses this data in order to calculate a valid landing target. The transform tree is set up as follows
.
When we look up the transform of a landing target (based on the ID of the detected tag) the goal is to chain the transforms until we have the position and orientation of the landing target within the same local reference frame that the drone uses to navigate. This information comes from a subscription to the uXRCE-DDS Bridged FMU topic /fmu/out/vehicle_local_position
. The orientation comes from the /fmu/out/vehicle_attitude
topic.
position_subscription_ = this->create_subscription<px4_msgs::msg::VehicleLocalPosition>(
"/fmu/out/vehicle_local_position",
qos_profile,
std::bind(&FramePublisher::handle_drone_position, this, std::placeholders::_1));
orientation_subscription_ = this->create_subscription<px4_msgs::msg::VehicleAttitude>(
"/fmu/out/vehicle_attitude",
qos_profile,
std::bind(&FramePublisher::handle_vehicle_attitude, this, std::placeholders::_1));
When this information is retrieved, the callbacks handle_drone_position
and handle_vehicle_attitude
store the most recent drone position and orientation into member variables.
There is a timer callback that then publishes the drone
to local
frame transform at a rate of 100hz.
transform_timer_ = this->create_wall_timer(
std::chrono::milliseconds(10),
std::bind(&FramePublisher::publish_transform, this));
void FramePublisher::publish_transform()
{
std::lock_guard<std::mutex> lock(*transform_mutex_);
if (latest_drone_orientation_ == nullptr || latest_drone_position_ == nullptr)
return;
geometry_msgs::msg::TransformStamped t;
t.header.stamp.sec = static_cast<int32_t>(latest_timestamp_ / 1000000);
t.header.stamp.nanosec = static_cast<uint32_t>((latest_timestamp_ % 1000000) * 1e3);
t.header.frame_id = "local";
t.child_frame_id = "base_link";
t.transform.translation.x = static_cast<double>(latest_drone_position_->x);
t.transform.translation.y = static_cast<double>(latest_drone_position_->y);
t.transform.translation.z = static_cast<double>(latest_drone_position_->z);
t.transform.rotation.w = static_cast<double>(latest_drone_orientation_->q[0]);
t.transform.rotation.x = static_cast<double>(latest_drone_orientation_->q[1]);
t.transform.rotation.y = static_cast<double>(latest_drone_orientation_->q[2]);
t.transform.rotation.z = static_cast<double>(latest_drone_orientation_->q[3]);
tf_broadcaster_->sendTransform(t);
}
All other frame transforms being published by the Transform Broadcaster are static and handled immediately with
void FramePublisher::make_static_transforms()
{
std::vector<geometry_msgs::msg::TransformStamped> static_transforms;
rclcpp::Time timestamp = this->get_clock()->now();
static_transforms.push_back(make_static_transform_camera(timestamp));
for (int i = 1; i <= 4 ; i++){
static_transforms.push_back(make_static_transform_apriltag(i, timestamp));
}
tf_static_broadcaster_->sendTransform(static_transforms);
}