Skip to content

Commit

Permalink
Succesfully runned simulation with ros2 control plugin and controllers
Browse files Browse the repository at this point in the history
  • Loading branch information
BartlomiejK2 committed Sep 14, 2024
1 parent 41336a1 commit f9e3e92
Show file tree
Hide file tree
Showing 6 changed files with 213 additions and 79 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -55,4 +55,6 @@
<xacro:gazebo_joint joint_name="BLS"/>
<xacro:gazebo_joint joint_name="BRS"/>

<!-- ROS2 Control -->
<xacro:include filename="ros2_control/ros2_control_gazebo.urdf.xacro"/>
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -7,29 +7,29 @@
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<!-- Transmissions -->
<xacro:include filename="ros2_control/transmission_macros.urdf.xacro"/>
<!-- <xacro:include filename="transmission_macros.urdf.xacro"/> -->

<!-- Hardware interface for Gazebo -->
<xacro:include filename="ros2_control/ros2_control_joint_macros.urdf.xacro"/>
<xacro:include filename="ros2_control_joint_macros.urdf.xacro"/>

<!-- Trunk to Hips joints-->
<xacro:ros2_control_joint joint_name="FLH_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FRH_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BLH_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BRH_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FLH" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FRH" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BLH" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BRH" lower="-${PI/2}" upper="${PI/2}"/>

<!-- Hips to Thighs joints -->
<xacro:ros2_control_joint joint_name="FLT_joint" lower="-${PI}" upper="${PI}"/>
<xacro:ros2_control_joint joint_name="FRT_joint" lower="-${PI}" upper="${PI}"/>
<xacro:ros2_control_joint joint_name="BLT_joint" lower="-${PI}" upper="${PI}"/>
<xacro:ros2_control_joint joint_name="BRT_joint" lower="-${PI}" upper="${PI}"/>
<xacro:ros2_control_joint joint_name="FLT" lower="-${PI}" upper="${PI}"/>
<xacro:ros2_control_joint joint_name="FRT" lower="-${PI}" upper="${PI}"/>
<xacro:ros2_control_joint joint_name="BLT" lower="-${PI}" upper="${PI}"/>
<xacro:ros2_control_joint joint_name="BRT" lower="-${PI}" upper="${PI}"/>


<!-- Thighs to Shanks joints -->
<xacro:ros2_control_joint joint_name="FLS_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FRS_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BLS_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BRS_joint" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FLS" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FRS" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BLS" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BRS" lower="-${PI/2}" upper="${PI/2}"/>

</ros2_control>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name ="meldog_ros2_control_joint_macros">

<xacro:include filename="actuator/actuator_macros.urdf.xacro"/>
<xacro:include filename="../actuator/actuator_macros.urdf.xacro"/>

<xacro:macro name="ros2_control_joint" params="joint_name upper lower"/>
<xacro:macro name="ros2_control_joint" params="joint_name upper lower">
<joint name="${joint_name}_joint">
<command_interface name="position">
<param name="min">${lower}</param>
Expand All @@ -13,11 +13,10 @@
<param name="min">-${actuator_max_velocity}</param>
<param name="max">${actuator_max_velocity}</param>
</command_interface>
<xacro:if value="$(arg use_gazebo)">
<command_interface name="effort"/>
<param name="min">-${actuator_max_torque}</param>
<param name="max">${actuator_max_torque}</param>
</xacro:if>
<command_interface name="effort">
<param name="min">-${actuator_max_torque}</param>
<param name="max">${actuator_max_torque}</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name ="meldog_transmissions">

<!-- SimpleTransmission macro -->
<xacro:macro name="SimpleTransmission" params="joint_name reduction offset"/>
<xacro:macro name="SimpleTransmission" params="joint_name reduction offset">
<transmission name="SimpleTransmission_${joint_name}">
<plugin>transmission_interface/SimpleTransmission</plugin>
<actuator name="${joint_name}_actuator" role="actuator1"/>
Expand All @@ -14,8 +14,8 @@
</xacro:macro>

<!-- FourBarLinkageTransmission macro -->
<xacro:macro name="FourBarLinkageTransmission" params="first_joint_name second__joint_name reduction first_offset second_offset"/>
<transmission name="FourBarLinkageTransmission_${first_joint_name}_${second__joint_name}">
<xacro:macro name="FourBarLinkageTransmission" params="first_joint_name second_joint_name reduction first_offset second_offset">
<transmission name="FourBarLinkageTransmission_${first_joint_name}_${second_joint_name}">
<plugin>transmission_interface/FourBarLinkageTransmission</plugin>
<actuator name="${first_joint_name}_actuator" role="actuator1">
<mechanical_reduction>${reduction}</mechanical_reduction>
Expand Down Expand Up @@ -43,9 +43,9 @@
<xacro:SimpleTransmission joint_name="BRH" reduction="9.97" offset="0.0"/>

<!-- Thighs to Shanks transmissions -->
<xacro:FourBarLinkageTransmission first_joint_name="FLT" second__joint_name="FLS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>
<xacro:FourBarLinkageTransmission first_joint_name="FRT" second__joint_name="FRS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>
<xacro:FourBarLinkageTransmission first_joint_name="BLT" second__joint_name="BLS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>
<xacro:FourBarLinkageTransmission first_joint_name="BRT" second__joint_name="BRS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>
<xacro:FourBarLinkageTransmission first_joint_name="FLT" second_joint_name="FLS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>
<xacro:FourBarLinkageTransmission first_joint_name="FRT" second_joint_name="FRS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>
<xacro:FourBarLinkageTransmission first_joint_name="BLT" second_joint_name="BLS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>
<xacro:FourBarLinkageTransmission first_joint_name="BRT" second_joint_name="BRS" reduction="9.97" first_offset="0.0" second_offset="0.0"/>

</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,157 @@
# Copyright 2020 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.

import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription, ExecuteProcess
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, RegisterEventHandler
from launch.conditions import IfCondition
from launch.event_handlers import OnProcessExit, OnProcessStart
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution

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

from launch_ros.parameter_descriptions import ParameterValue

from launch_ros.actions import Node


def generate_launch_description():

# Declare arguments
declared_arguments = []

declared_arguments.append(
DeclareLaunchArgument(
"package",
default_value="meldog_simple_description",
)
)

declared_arguments.append(
DeclareLaunchArgument(
"urdf_file",
default_value="meldog_gazebo.urdf.xacro",
)
)

declared_arguments.append(
DeclareLaunchArgument(
"controller_type_file",
default_value="joint_trajectory_controller_test.yaml",
)
)

declared_arguments.append(
DeclareLaunchArgument(
"controller_type",
default_value="joint_trajectory_controller",
)
)

# Initialize Arguments
package_name = LaunchConfiguration("package")
urdf_file = LaunchConfiguration("urdf_file")
controller_file = LaunchConfiguration("controller_type_file")
controller_type = LaunchConfiguration("controller_type")


# Get URDF via xacro
robot_description_content = ParameterValue(
Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[
FindPackageShare(package_name),
"description",
urdf_file,
]
),
]
), value_type=str)

# Set up dictionary parameters:
robot_description = {"robot_description": robot_description_content}
use_sim_time = {"use_sim_time": True}

# Load world for gazebo sim
world = PathJoinSubstitution(
[
FindPackageShare(package_name),
"worlds",
'empty.world'
]
)

# robot_state_publisher node:
robot_state_pub_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description, use_sim_time],
)

# Spawn Meldog:
spawn_entity = Node(package='ros_gz_sim', executable='create',
arguments=['-topic', 'robot_description',
'-name', 'Meldog'],
output='screen')

# Load joint_state_broadcaster
load_joint_state_broadcaster = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
'joint_state_broadcaster'],
output='screen'
)

# Load joint_trajectory_controller
load_joint_effort_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', controller_type],
output='screen'
)

# Bridge between ros2 and Ignition Gazebo
ros2_gazebo_sim_bridge = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory('ros_ign_gazebo'),
'launch', 'ign_gazebo.launch.py')]),
launch_arguments=[('gz_args', [' -r -v 4 empty.sdf'])])

nodes = [
ros2_gazebo_sim_bridge,

RegisterEventHandler(
event_handler=OnProcessExit(
target_action=spawn_entity,
on_exit=[load_joint_state_broadcaster],
)
),

RegisterEventHandler(
event_handler=OnProcessExit(
target_action= load_joint_state_broadcaster,
on_exit=[load_joint_effort_controller],
)
),

robot_state_pub_node,
spawn_entity,
]
return LaunchDescription(declared_arguments + nodes)
Loading

0 comments on commit f9e3e92

Please sign in to comment.