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 Demos for SDF #427

Merged
merged 10 commits into from
Dec 4, 2024
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions gz_ros2_control_demos/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ find_package(geometry_msgs REQUIRED)
install(DIRECTORY
launch
config
sdf
urdf
DESTINATION share/${PROJECT_NAME}/
)
Expand Down
107 changes: 107 additions & 0 deletions gz_ros2_control_demos/launch/diff_drive_example_sdf.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
# Copyright 2022 Open Source Robotics Foundation, Inc.
Copy link
Collaborator

Choose a reason for hiding this comment

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

Suggested change
# Copyright 2022 Open Source Robotics Foundation, Inc.
# Copyright 2024 Open Source Robotics Foundation, Inc.

#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.actions import RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution

from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
# Launch Arguments
use_sim_time = LaunchConfiguration('use_sim_time', default=True)

# Get URDF via xacro
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name='xacro')]),
' ',
PathJoinSubstitution(
[FindPackageShare('gz_ros2_control_demos'),
'sdf', 'test_diff_drive.xacro.sdf']
),
]
)
Copy link
Collaborator

Choose a reason for hiding this comment

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

you don't need to do that, the sdf file doesn't have any xacro tag. You should read the file as it's

Copy link
Collaborator

Choose a reason for hiding this comment

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

you should be able to use something like from launch.substitutions import FileContent

robot_description = {'robot_description': robot_description_content}
robot_controllers = PathJoinSubstitution(
[
FindPackageShare('gz_ros2_control_demos'),
'config',
'diff_drive_controller_velocity.yaml',
]
)

node_robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[robot_description]
)

gz_spawn_entity = Node(
package='ros_gz_sim',
executable='create',
output='screen',
arguments=['-topic', 'robot_description', '-name',
'diff_drive', '-allow_renaming', 'true'],
)

joint_state_broadcaster_spawner = Node(
package='controller_manager',
executable='spawner',
arguments=['joint_state_broadcaster'],
)
diff_drive_base_controller_spawner = Node(
package='controller_manager',
executable='spawner',
arguments=[
'diff_drive_base_controller',
'--param-file',
robot_controllers,
],
)

return LaunchDescription([
# Launch gazebo environment
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[PathJoinSubstitution([FindPackageShare('ros_gz_sim'),
'launch',
'gz_sim.launch.py'])]),
launch_arguments=[('gz_args', [' -r -v 4 empty.sdf'])]),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=gz_spawn_entity,
on_exit=[joint_state_broadcaster_spawner],
)
),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[diff_drive_base_controller_spawner],
)
),
node_robot_state_publisher,
gz_spawn_entity,
# Launch Arguments
DeclareLaunchArgument(
'use_sim_time',
default_value=use_sim_time,
description='If true, use simulated clock'),
])
219 changes: 219 additions & 0 deletions gz_ros2_control_demos/sdf/test_diff_drive.xacro.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,219 @@
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="diff_drive" canonical_link="base_link">
<link name="base_link">
<must_be_base_link>true</must_be_base_link>
</link>

<joint name="chassis_joint" type="fixed">
<parent>base_link</parent>
<child>chassis</child>
<pose relative_to="base_link">-0.151427 -0 0.5 0 0 0</pose>
</joint>

<link name="chassis">
<pose relative_to="chassis_joint"/>
<visual name="chassis_visual">
<geometry>
<box><size>
2.01142 1 0.568726
</size></box>
</geometry>
<material>
<ambient>1 0.5088 0.0468 1</ambient>
<diffuse>1 0.5088 0.0468 1</diffuse>
</material>
</visual>

<collision name="chassis_collision">
<geometry>
<box><size>
2.01142 1 0.568726
</size></box>
</geometry>
</collision>

<inertial>
<mass>1.14395</mass>
<inertia>
<ixx>0.126164</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.416519</iyy>
<iyz>0.0</iyz>
<izz>0.481014</izz>
</inertia>
</inertial>
</link>

<joint name="left_wheel_joint" type="revolute">
<parent>chassis</parent>
<child>left_wheel</child>
<pose relative_to="chassis">0.554283 0.625029 -0.3 -1.5707 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-inf</lower>
<upper>inf</upper>
</limit>
<dynamics>
<damping>0.2</damping>
</dynamics>
</axis>
</joint>

<link name="left_wheel">
<pose relative_to="left_wheel_joint"/>
<visual name="left_wheel_visual">
<geometry>
<sphere><radius>
0.3
</radius></sphere>
</geometry>
<material>
<ambient>0 0 0 1</ambient>
<diffuse>0 0 0 1</diffuse>
</material>
</visual>

<collision name="left_wheel_collision">
<geometry>
<sphere><radius>
0.3
</radius></sphere>
</geometry>
</collision>

<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.145833</iyy>
<iyz>0.0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
</link>

<joint name="right_wheel_joint" type="revolute">
<parent>chassis</parent>
<child>right_wheel</child>
<pose relative_to="chassis">0.554283 -0.625029 -0.3 -1.5707 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-inf</lower>
<upper>inf</upper>
</limit>
<dynamics>
<damping>0.2</damping>
</dynamics>
</axis>
</joint>

<link name="right_wheel">
<pose relative_to="right_wheel_joint"/>
<visual name="right_wheel_visual">
<geometry>
<sphere><radius>
0.3
</radius></sphere>
</geometry>
<material>
<ambient>0 0 0 1</ambient>
<diffuse>0 0 0 1</diffuse>
</material>
</visual>

<collision name="right_wheel_collision">
<geometry>
<sphere><radius>
0.3
</radius></sphere>
</geometry>
</collision>

<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.145833</iyy>
<iyz>0.0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
</link>

<joint name="caster_joint" type="fixed">
<parent>chassis</parent>
<child>caster</child>
<pose relative_to="chassis">-0.80571 0 -0.2 0 0 0</pose>
</joint>

<link name="caster">
<pose relative_to="caster_joint"/>
<visual name="caster_visual">
<geometry>
<sphere><radius>
0.2
</radius></sphere>
</geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>1 1 1 1</diffuse>
</material>
</visual>

<collision name="caster_collision">
<geometry>
<sphere><radius>
0.2
</radius></sphere>
</geometry>
</collision>

<inertial>
<mass>0.005</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.1</iyy>
<iyz>0.0</iyz>
<izz>0.1</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">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>

<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<parameters>$(find gz_ros2_control_demos)/config/diff_drive_controller_velocity.yaml</parameters>
</plugin>

</model>
</sdf>