Skip to content

Commit

Permalink
add plugin to publish TF between two links attached to the same model
Browse files Browse the repository at this point in the history
  • Loading branch information
stibipet committed Mar 18, 2024
1 parent 5ce9745 commit 3c5efa0
Show file tree
Hide file tree
Showing 2 changed files with 95 additions and 0 deletions.
13 changes: 13 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,7 @@ set(LIBRARIES
MrsGazeboCommonResources_FluidResistancePlugin
MrsGazeboCommonResources_MotorSpeedRepublisherPlugin
MrsGazeboCommonResources_MotorPropModelPlugin
MrsGazeboCommonResources_LinkStaticTFPublisher
)

catkin_package(
Expand Down Expand Up @@ -371,6 +372,18 @@ target_link_libraries(MrsGazeboCommonResources_MotorPropModelPlugin
${Boost_LIBRARIES}
)

# LinkStaticTFPublisher

add_library(MrsGazeboCommonResources_LinkStaticTFPublisher SHARED
src/sensor_and_model_plugins/link_static_tf_publisher.cpp
)

target_link_libraries(MrsGazeboCommonResources_LinkStaticTFPublisher
${GAZEBO_LIBRARIES}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

## --------------------------------------------------------------
## | Install |
## --------------------------------------------------------------
Expand Down
82 changes: 82 additions & 0 deletions src/sensor_and_model_plugins/link_static_tf_publisher.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
/* Mostly generated using ChatGPT 3.5 */

#include <gazebo/common/Plugin.hh>
#include <gazebo/common/common.hh>
#include <gazebo/physics/physics.hh>
#include <ros/ros.h>
#include <tf2_msgs/TFMessage.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/static_transform_broadcaster.h>

namespace gazebo
{

class LinkStaticTFPublisher : public ModelPlugin {
private:
physics::ModelPtr model;
tf2_ros::StaticTransformBroadcaster tf_broadcaster;

public:
LinkStaticTFPublisher() {
}

virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) {
// Safety check
if (!_model) {
ROS_ERROR("[LinkStaticTFPublisher]: Invalid model pointer!");
return;
}

model = _model;

std::string parentLinkName;
std::string childLinkName;

if (_sdf->HasElement("parentLink")) {
parentLinkName = _sdf->Get<std::string>("parentLink");
}else{
ROS_ERROR("[LinkStaticTFPublisher]: SDF is missing element \"parentLink\"");
return;
}

if (_sdf->HasElement("childLink")) {
childLinkName = _sdf->Get<std::string>("childLink");
}else{
ROS_ERROR("[LinkStaticTFPublisher]: SDF is missing element \"childLink\"");
return;
}

// Get pointers to the specified parent and child links
physics::LinkPtr parentLink = model->GetLink(parentLinkName);
physics::LinkPtr childLink = model->GetLink(childLinkName);

// Check if both links are valid
if (!parentLink || !childLink) {
ROS_ERROR_STREAM("[LinkStaticTFPublisher]: One or both of the links \"" << parentLinkName << "\", \"" << childLinkName << "\" do not exist!");
return;
}

// Get the transform between the parent and child links
ignition::math::Pose3d relativePose = childLink->WorldPose() - parentLink->WorldPose();

tf2::Quaternion quat(relativePose.Rot().X(), relativePose.Rot().Y(), relativePose.Rot().Z(), relativePose.Rot().W());

// Publish the transform
geometry_msgs::TransformStamped transformStamped;
transformStamped.header.stamp = ros::Time::now();
transformStamped.header.frame_id = parentLinkName;
transformStamped.child_frame_id = childLinkName;
transformStamped.transform.translation.x = relativePose.Pos().X();
transformStamped.transform.translation.y = relativePose.Pos().Y();
transformStamped.transform.translation.z = relativePose.Pos().Z();
transformStamped.transform.rotation.w = relativePose.Rot().W();
transformStamped.transform.rotation.x = relativePose.Rot().X();
transformStamped.transform.rotation.y = relativePose.Rot().Y();
transformStamped.transform.rotation.z = relativePose.Rot().Z();
tf_broadcaster.sendTransform(transformStamped);
ROS_INFO_STREAM("[LinkStaticTFPublisher]: Published static TF between frames \"" << parentLinkName << "\", \"" << childLinkName << "\"");
}
};

GZ_REGISTER_MODEL_PLUGIN(LinkStaticTFPublisher)
} // namespace gazebo

0 comments on commit 3c5efa0

Please sign in to comment.