Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Support for SDF #1763

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open

Conversation

Amronos
Copy link

@Amronos Amronos commented Sep 25, 2024

Fixes #632
I have modified hardware_interface/src/component_parser.cpp to add support for SDF models.

To test this out, something like the following SDF file can be passed to robot_state_publisher instead of a URDF file alongside using it to spawn the robot into the gazebo world. I do plan to make a PR into gz_ros2_control_demos to add a demo for this.

<?xml version="1.0" ?>
<sdf version="1.8">
  <model canonical_link="base_link" name="my_robot">
    <!-- BASE -->
    <link name="base_link">
      <must_be_base_link>true</must_be_base_link>
    </link>
    <!-- CHASSIS -->
    <joint name="chassis_joint" type="fixed">
      <parent>base_link</parent>
      <child>chassis_link</child>
      <pose relative_to="base_link">0 0 0.075 0 0 0</pose>
    </joint>
    <link name="chassis_link">
      <pose relative_to="chassis_joint"/>
      <visual name="chassis_link_visual">
        <geometry>
          <box>
            <size>
                0.3 0.3 0.15
              </size>
          </box>
        </geometry>
        <material>
          <ambient>1 1 1 1</ambient>
          <diffuse>1 1 1 1</diffuse>
        </material>
      </visual>
      <collision name="chassis_link_collision">
        <geometry>
          <box>
            <size>
                0.3 0.3 0.15
              </size>
          </box>
        </geometry>
      </collision>
      <inertial>
        <mass>0.5</mass>
        <inertia>
          <ixx>0.0046875</ixx>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyy>0.0046875</iyy>
          <iyz>0.0</iyz>
          <izz>0.0075</izz>
        </inertia>
      </inertial>
    </link>
    <!-- lEFT WHEEL -->
    <joint name="left_wheel_joint" type="revolute">
      <parent>chassis_link</parent>
      <child>left_wheel_link</child>
      <pose relative_to="chassis_link">0.09 0.16999999999999998 -0.075 -1.5707963267948966 0 0</pose>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-inf</lower>
          <upper>inf</upper>
        </limit>
      </axis>
    </joint>
    <link name="left_wheel_link">
      <pose relative_to="left_wheel_joint"/>
      <visual name="left_wheel_link_visual">
        <geometry>
          <cylinder>
            <radius>0.05</radius>
            <length>0.04</length>
          </cylinder>
        </geometry>
        <material>
          <ambient>0 0 1</ambient>
          <diffuse>0 0 1</diffuse>
        </material>
      </visual>
      <collision name="left_wheel_link_collision">
        <geometry>
          <cylinder>
            <radius>0.05</radius>
            <length>0.04</length>
          </cylinder>
        </geometry>
      </collision>
      <inertial>
        <mass>0.1</mass>
        <inertia>
          <ixx>7.583333333333335e-05</ixx>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyy>7.583333333333335e-05</iyy>
          <iyz>0.0</iyz>
          <izz>0.00012500000000000003</izz>
        </inertia>
      </inertial>
    </link>
    <!-- RIGHT WHEEL -->
    <joint name="right_wheel_joint" type="revolute">
      <parent>chassis_link</parent>
      <child>right_wheel_link</child>
      <pose relative_to="chassis_link">0.09 -0.16999999999999998 -0.075 -1.5707963267948966 0 0</pose>
      <axis>
        <xyz>0 0 1</xyz>
        <!-- limit would not be specified because if the type was continuous -->
        <limit>
          <lower>-inf</lower>
          <upper>inf</upper>
        </limit>
      </axis>
    </joint>
    <link name="right_wheel_link">
      <pose relative_to="right_wheel_joint"/>
      <visual name="right_wheel_link_visual">
        <geometry>
          <cylinder>
            <radius>0.05</radius>
            <length>0.04</length>
          </cylinder>
        </geometry>
        <material>
          <ambient>0 0 1</ambient>
          <diffuse>0 0 1</diffuse>
        </material>
      </visual>
      <collision name="right_wheel_link_collision">
        <geometry>
          <cylinder>
            <radius>0.05</radius>
            <length>0.04</length>
          </cylinder>
        </geometry>
      </collision>
      <inertial>
        <mass>0.1</mass>
        <inertia>
          <ixx>7.583333333333335e-05</ixx>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyy>7.583333333333335e-05</iyy>
          <iyz>0.0</iyz>
          <izz>0.00012500000000000003</izz>
        </inertia>
      </inertial>
    </link>
    <!-- CASTER -->
    <joint name="caster_joint" type="revolute">
      <parent>chassis_link</parent>
      <child>caster_link</child>
      <pose relative_to="chassis_link">-0.09 0 -0.075 0 0 0</pose>
      <axis>
        <xyz>1 1 1</xyz>
        <limit>
          <lower>-inf</lower>
          <upper>inf</upper>
        </limit>
      </axis>
    </joint>
    <link name="caster_link">
      <pose relative_to="caster_joint"/>
      <visual name="caster_link_visual">
        <geometry>
          <sphere>
            <radius>0.05</radius>
          </sphere>
        </geometry>
        <material>
          <ambient>0 0 1</ambient>
          <diffuse>0 0 1</diffuse>
        </material>
      </visual>
      <collision name="caster_link_collision">
        <geometry>
          <sphere>
            <radius>0.05</radius>
          </sphere>
        </geometry>
      </collision>
      <inertial>
        <mass>0.1</mass>
        <inertia>
          <ixx>0.00010000000000000002</ixx>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyy>0.00010000000000000002</iyy>
          <iyz>0.0</iyz>
          <izz>0.00010000000000000002</izz>
        </inertia>
      </inertial>
    </link>
    <ros2_control name="GazeboSimSystem" type="system">
      <hardware>
        <plugin>gz_ros2_control/GazeboSimSystem</plugin>
      </hardware>
      <joint name="left_wheel_joint">
        <command_interface name="velocity">
          <param name="min">-10</param>
          <param name="max">10</param>
        </command_interface>
        <state_interface name="velocity"/>
        <state_interface name="position"/>
      </joint>
      <joint name="right_wheel_joint">
        <command_interface name="velocity">
          <param name="min">-10</param>
          <param name="max">10</param>
        </command_interface>
        <state_interface name="velocity"/>
        <state_interface name="position"/>
      </joint>
    </ros2_control>
    <plugin filename="libgz_ros2_control-system.so" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
      <parameters>/home/amronos/ros2_ws/install/my_robot/share/my_robot/config/my_controllers.yaml</parameters>
    </plugin>
  </model>
</sdf>

Signed-off-by: Aarav Gupta <[email protected]>
Copy link
Member

@saikishor saikishor left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link

codecov bot commented Sep 25, 2024

Codecov Report

Attention: Patch coverage is 16.66667% with 5 lines in your changes missing coverage. Please review.

Project coverage is 86.74%. Comparing base (84e85f9) to head (424228b).
Report is 1 commits behind head on master.

Files with missing lines Patch % Lines
hardware_interface/src/component_parser.cpp 16.66% 4 Missing and 1 partial ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##           master    #1763      +/-   ##
==========================================
- Coverage   86.79%   86.74%   -0.06%     
==========================================
  Files         116      116              
  Lines       10715    10719       +4     
  Branches      981      982       +1     
==========================================
- Hits         9300     9298       -2     
- Misses       1062     1067       +5     
- Partials      353      354       +1     
Flag Coverage Δ
unittests 86.74% <16.66%> (-0.06%) ⬇️

Flags with carried forward coverage won't be shown. Click here to find out more.

Files with missing lines Coverage Δ
hardware_interface/src/component_parser.cpp 93.68% <16.66%> (-0.75%) ⬇️

... and 1 file with indirect coverage changes

Copy link
Member

@saikishor saikishor left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@Amronos The changes look good to me. Can you add that SDF parsing is also supported through robot_description topic in the release_notes.rst?.

Sorry for not pointing out earlier

Signed-off-by: Aarav Gupta <[email protected]>
Copy link
Member

@saikishor saikishor left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

@azeey
Copy link

azeey commented Oct 3, 2024

This is great! Thanks @Amronos

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Use ros2 control with sdf model
3 participants