[Documentation] [TitleIndex] [WordIndex

closed_loop_plugin

This is pegasus_gazebo_plugins package developed for our quadruped robot "Pegasus",which is used for Pegasus robots in gazebo simulation and ROS environment.closed_loop_plugin is one of the plugins that open here,to solve the issue that URDF not support Closed loop chains.

For more information, please refer tohttps://github.com/wojiaojiao/pegasus_gazebo_plugins

Introduction

The URDF served the ROS, it has several notable shortcomings.one is it does not support closed loop chains. The SDF served the gazebo, support closed loop chains - this can be achieved by allowing two different joints to have the same child link but different parents The closed_loop_plugin works after the robot model is converted from urdf to sdf, inserting a new joint into the SDF.

  • https://raw.githubusercontent.com/wojiaojiao/pegasus_gazebo_plugins/master/doc/diagram2.png

Building

In order to install the pegasus_gazebo_plugins, clone the latest version from this repository into your catkin workspace and compile the package using ROS.

 cd catkin_workspace/src
 git clone https://github.com/wojiaojiao/pegasus_gazebo_plugins.git
 cd ../
 catkin_make

Usage

This closed_loop_plugin just like a button that connects two joints

  • <joint>the name of the added joint

  • <child> the name that child coordinate of the added joint

  • <parent> the name that parent coordinate of the added joint

add to your robot.urdf:

<gazebo>
  <plugin name="Myrobot_ClosedLoopPlugin" filename="libpegasus_gazebo_closed_loop_plugin.so">
    <joint>add_joint</joint> <child>add_joint_child_link</child> 
    <parent>add_joint_parent_link</parent>
  </plugin>
</gazebo>

{*} note: You can change the position where two joints are connected in closed_loop_plugin.cpp

  • math::Pose jointOrigin(x,y,z,roll,pitch,yaw);

math::Pose jointOrigin(0.00,0.00,0.00,0.00,-0.00,0.00);

2022-05-28 12:17