feat: add webots integration

This commit is contained in:
Ilya Uraev 2025-06-03 01:21:06 +03:00
parent a10ded747a
commit 033e14d80e
7 changed files with 524 additions and 243 deletions

View file

@ -0,0 +1,131 @@
#!/usr/bin/env python
# Copyright 1996-2023 Cyberbotics Ltd.
#
# 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.
"""Launch Webots Universal Robot simulation nodes."""
import os
import launch
from launch_ros.actions import Node
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.urdf_spawner import URDFSpawner, get_webots_driver_node
from webots_ros2_driver.webots_controller import WebotsController
from rbs_utils.launch import load_xacro_args
from robot_builder.external.ros2_control import ControllerManager
from robot_builder.parser.urdf import URDF_parser
import xacro
PACKAGE_NAME = 'aubo_description'
def generate_launch_description():
package_dir = get_package_share_directory(PACKAGE_NAME)
robot_description_path = os.path.join(package_dir, 'urdf', 'aubo_i5.urdf.xacro')
controllers_file = os.path.join(package_dir, 'config', 'controllers.yaml')
mappings_data = load_xacro_args(robot_description_path, locals())
robot_description_doc = xacro.process_file(
robot_description_path, mappings={"robot_ip": "", "simulation_controllers": controllers_file, "hardware": "webots", "with_gripper": "false"}
)
robot_description_content = robot_description_doc.toprettyxml(indent=" ")
# with open("current.urdf", "w") as file:
# file.write(robot_description_content)
# file.close()
robot = URDF_parser.load_string(
robot_description_content,
base_link_name="base_link",
ee_link_name="wrist3_Link",
)
ControllerManager.save_to_yaml(
robot, package_dir, "controllers.yaml"
)
# Define your URDF robots here
# The name of an URDF robot has to match the name of the robot of the driver node
# You can specify the URDF file to use with "urdf_path"
spawn_URDF_aubo = URDFSpawner(
name='Aubo-i5',
robot_description=robot_description_content,
translation='0 0 0.6',
rotation='0 0 1 -1.5708',
)
# Driver nodes
# When having multiple robot it is mandatory to specify the robot name.
aubo_robot_driver = WebotsController(
robot_name='Aubo-i5',
parameters=[
{'robot_description': robot_description_content},
{'use_sim_time': True},
{'set_robot_state_publisher': True},
controllers_file
],
)
# Other ROS 2 nodes
controller_manager_timeout = ['--controller-manager-timeout', '100']
trajectory_controller_spawner = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['cartesian_motion_controller'] + controller_manager_timeout,
)
joint_state_broadcaster_spawner = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['joint_state_broadcaster'] + controller_manager_timeout,
)
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[{
'robot_description': '<robot name=""><link name=""/></robot>'
}],
)
return LaunchDescription([
# Request to spawn the URDF robot
spawn_URDF_aubo,
# Other ROS 2 nodes
robot_state_publisher,
trajectory_controller_spawner,
joint_state_broadcaster_spawner,
# Launch the driver node once the URDF robot is spawned
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessIO(
target_action=spawn_URDF_aubo,
on_stdout=lambda event: get_webots_driver_node(event, aubo_robot_driver),
)
),
# Kill all the nodes when the driver node is shut down
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=aubo_robot_driver,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
)
),
])

View file

@ -0,0 +1,55 @@
#!/usr/bin/env python
# Copyright 1996-2023 Cyberbotics Ltd.
#
# 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.
"""Launch Webots Universal Robot simulation world."""
import launch
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.substitutions.path_join_substitution import PathJoinSubstitution
from webots_ros2_driver.webots_launcher import WebotsLauncher
PACKAGE_NAME = 'aubo_description'
def generate_launch_description():
package_dir = get_package_share_directory(PACKAGE_NAME)
world = LaunchConfiguration('world')
# Starts Webots
webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'world', world]),
ros2_supervisor=True
)
return LaunchDescription([
DeclareLaunchArgument(
'world',
default_value='aubo_robot.wbt',
),
webots,
webots._supervisor,
# This action will kill all nodes once the Webots simulation has exited
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
)
)
])

View file

@ -1,220 +1,275 @@
<?xml version="1.0"?>
<robot name="aubo_i5">
<link name="base_link">
<inertial>
<origin xyz="-1.4795E-13 0.0015384 0.020951" rpy="0 0 0" />
<mass value="0.83419" />
<inertia ixx="0.0014414" ixy="7.8809E-15" ixz="8.5328E-16" iyy="0.0013542" iyz="-1.4364E-05" izz="0.0024659" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/base_link.DAE" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/base_link.STL" />
</geometry>
</collision>
</link>
<link name="shoulder_Link">
<inertial>
<origin xyz="3.2508868974735E-07 0.00534955349296065 -0.00883689325611056" rpy="0 0 0" />
<mass value="1.57658348693929" />
<inertia ixx="0.0040640448663128" ixy="0" ixz="0" iyy="0.00392863238466817" iyz="-0.000160151642851425" izz="0.0030869857349184" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/shoulder_Link.DAE" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/shoulder_Link.STL" />
</geometry>
</collision>
</link>
<joint name="shoulder_joint" type="revolute">
<origin xyz="0 0 0.122" rpy="0 0 3.1416" />
<parent link="base_link" />
<child link="shoulder_Link" />
<axis xyz="0 0 1" />
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
</joint>
<link name="upperArm_Link">
<inertial>
<origin xyz="0.203996646979614 2.01304585036544E-10 0.0127641545395984" rpy="0 0 0" />
<mass value="4.04175782265494" />
<inertia ixx="0.00965399211106204" ixy="0" ixz="0" iyy="0.144993869035655" iyz="0" izz="0.142607184038966" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/upperArm_Link.DAE" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/upperArm_Link.STL" />
</geometry>
</collision>
</link>
<joint name="upperArm_joint" type="revolute">
<origin xyz="0 0.1215 0" rpy="-1.5708 -1.5708 0" />
<parent link="shoulder_Link" />
<child link="upperArm_Link" />
<axis xyz="0 0 1" />
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
</joint>
<link name="foreArm_Link">
<inertial>
<origin xyz="0.188922115560337 6.78882434739072E-07 0.0981026740461557" rpy="0 0 0" />
<mass value="2.27145669098343" />
<inertia ixx="0.00214322284946289" ixy="0" ixz="-0.00073120631553383" iyy="0.0443926090878205" iyz="0" izz="0.0441273797128365" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/foreArm_Link.DAE" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/foreArm_Link.STL" />
</geometry>
</collision>
</link>
<joint name="foreArm_joint" type="revolute">
<origin xyz="0.408 0 0" rpy="-3.1416 -5.1632E-18 -5.459E-16" />
<parent link="upperArm_Link" />
<child link="foreArm_Link" />
<axis xyz="0 0 1" />
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
</joint>
<link name="wrist1_Link">
<inertial>
<origin xyz="7.54205137428592E-07 0.0062481254331257 -0.00392367464072373" rpy="0 0 0" />
<mass value="0.500477539188764" />
<inertia ixx="0.00071194605962081" ixy="0" ixz="0" iyy="0.00040588242872958" iyz="-2.30808694377512E-05" izz="0.000685574004861334" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist1_Link.DAE" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist1_Link.STL" />
</geometry>
</collision>
</link>
<joint name="wrist1_joint" type="revolute">
<origin xyz="0.376 0 0" rpy="3.1416 -1.8323E-15 1.5708" />
<parent link="foreArm_Link" />
<child link="wrist1_Link" />
<axis xyz="0 0 1" />
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
</joint>
<link name="wrist2_Link">
<inertial>
<origin xyz="-7.54207620578635E-07 -0.00624812542617262 -0.00392367464115684" rpy="0 0 0" />
<mass value="0.500477539245988" />
<inertia ixx="0.00071194605981829" ixy="0" ixz="0" iyy="0.000405882428755442" iyz="2.30808694515886E-05" izz="0.000685574005112107" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist2_Link.DAE" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist2_Link.STL" />
</geometry>
</collision>
</link>
<joint name="wrist2_joint" type="revolute">
<origin xyz="0 0.1025 0" rpy="-1.5708 -1.8709E-15 -1.6653E-16" />
<parent link="wrist1_Link" />
<child link="wrist2_Link" />
<axis xyz="0 0 1" />
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
</joint>
<link name="wrist3_Link">
<inertial>
<origin xyz="3.92048778449938E-10 0.000175788057281467 -0.0213294490706684" rpy="0 0 0" />
<mass value="0.158309554874285" />
<inertia ixx="7.31376196034769E-05" ixy="0" ixz="0" iyy="7.19528188876563E-05" iyz="0" izz="0.000108772439051422" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist3_Link.DAE" />
</geometry>
<material name="">
<color rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist3_Link.STL" />
</geometry>
</collision>
</link>
<joint name="wrist3_joint" type="revolute">
<origin xyz="0 -0.094 0" rpy="1.5708 0 1.7907E-15" />
<parent link="wrist2_Link" />
<child link="wrist3_Link" />
<axis xyz="0 0 1" />
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
</joint>
<link name="world" />
<joint name="world_joint" type="fixed">
<parent link="world" />
<child link = "base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>
</robot>
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/narenmak/rbs_ws/install/aubo_description/share/aubo_description/urdf/aubo_i5.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="aubo_i5">
<material name="black">
<color rgba="0.25098 0.25098 0.25098 1"/>
</material>
<material name="orange">
<color rgba="1.0 0.4235294117647059 0.0392156862745098 1.0"/>
</material>
<material name="white">
<color rgba="0.68627 0.69804 0.67451 1"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="-1.4795E-13 0.0015384 0.020951"/>
<mass value="0.83419"/>
<inertia ixx="0.0014414" ixy="7.8809E-15" ixz="8.5328E-16" iyy="0.0013542" iyz="-1.4364E-05" izz="0.0024659"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/base_link.DAE"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/base_link.STL"/>
</geometry>
</collision>
</link>
<link name="shoulder_Link">
<inertial>
<origin rpy="0 0 0" xyz="3.2508868974735E-07 0.00534955349296065 -0.00883689325611056"/>
<mass value="1.57658348693929"/>
<inertia ixx="0.0040640448663128" ixy="0" ixz="0" iyy="0.00392863238466817" iyz="-0.000160151642851425" izz="0.0030869857349184"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/shoulder_Link.DAE"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/shoulder_Link.STL"/>
</geometry>
</collision>
</link>
<joint name="shoulder_joint" type="revolute">
<origin rpy="0 0 3.1416" xyz="0 0 0.122"/>
<parent link="base_link"/>
<child link="shoulder_Link"/>
<axis xyz="0 0 1"/>
<limit effort="150" lower="-6.28" upper="6.28" velocity="3.1416"/>
</joint>
<link name="upperArm_Link">
<inertial>
<origin rpy="0 0 0" xyz="0.203996646979614 2.01304585036544E-10 0.0127641545395984"/>
<mass value="4.04175782265494"/>
<inertia ixx="0.00965399211106204" ixy="0" ixz="0" iyy="0.144993869035655" iyz="0" izz="0.142607184038966"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/upperArm_Link.DAE"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/upperArm_Link.STL"/>
</geometry>
</collision>
</link>
<joint name="upperArm_joint" type="revolute">
<origin rpy="-1.5708 -1.5708 0" xyz="0 0.1215 0"/>
<parent link="shoulder_Link"/>
<child link="upperArm_Link"/>
<axis xyz="0 0 1"/>
<limit effort="150" lower="-6.28" upper="6.28" velocity="3.1416"/>
</joint>
<link name="foreArm_Link">
<inertial>
<origin rpy="0 0 0" xyz="0.188922115560337 6.78882434739072E-07 0.0981026740461557"/>
<mass value="2.27145669098343"/>
<inertia ixx="0.00214322284946289" ixy="0" ixz="-0.00073120631553383" iyy="0.0443926090878205" iyz="0" izz="0.0441273797128365"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/foreArm_Link.DAE"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/foreArm_Link.STL"/>
</geometry>
</collision>
</link>
<joint name="foreArm_joint" type="revolute">
<origin rpy="-3.1416 -5.1632E-18 -5.459E-16" xyz="0.408 0 0"/>
<parent link="upperArm_Link"/>
<child link="foreArm_Link"/>
<axis xyz="0 0 1"/>
<limit effort="150" lower="-6.28" upper="6.28" velocity="3.1416"/>
</joint>
<link name="wrist1_Link">
<inertial>
<origin rpy="0 0 0" xyz="7.54205137428592E-07 0.0062481254331257 -0.00392367464072373"/>
<mass value="0.500477539188764"/>
<inertia ixx="0.00071194605962081" ixy="0" ixz="0" iyy="0.00040588242872958" iyz="-2.30808694377512E-05" izz="0.000685574004861334"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist1_Link.DAE"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist1_Link.STL"/>
</geometry>
</collision>
</link>
<joint name="wrist1_joint" type="revolute">
<origin rpy="3.1416 -1.8323E-15 1.5708" xyz="0.376 0 0"/>
<parent link="foreArm_Link"/>
<child link="wrist1_Link"/>
<axis xyz="0 0 1"/>
<limit effort="28" lower="-6.28" upper="6.28" velocity="3.1416"/>
</joint>
<link name="wrist2_Link">
<inertial>
<origin rpy="0 0 0" xyz="-7.54207620578635E-07 -0.00624812542617262 -0.00392367464115684"/>
<mass value="0.500477539245988"/>
<inertia ixx="0.00071194605981829" ixy="0" ixz="0" iyy="0.000405882428755442" iyz="2.30808694515886E-05" izz="0.000685574005112107"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist2_Link.DAE"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist2_Link.STL"/>
</geometry>
</collision>
</link>
<joint name="wrist2_joint" type="revolute">
<origin rpy="-1.5708 -1.8709E-15 -1.6653E-16" xyz="0 0.1025 0"/>
<parent link="wrist1_Link"/>
<child link="wrist2_Link"/>
<axis xyz="0 0 1"/>
<limit effort="28" lower="-6.28" upper="6.28" velocity="3.1416"/>
</joint>
<link name="wrist3_Link">
<inertial>
<origin rpy="0 0 0" xyz="3.92048778449938E-10 0.000175788057281467 -0.0213294490706684"/>
<mass value="0.158309554874285"/>
<inertia ixx="7.31376196034769E-05" ixy="0" ixz="0" iyy="7.19528188876563E-05" iyz="0" izz="0.000108772439051422"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist3_Link.DAE"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist3_Link.STL"/>
</geometry>
</collision>
</link>
<joint name="wrist3_joint" type="revolute">
<origin rpy="1.5708 0 1.7907E-15" xyz="0 -0.094 0"/>
<parent link="wrist2_Link"/>
<child link="wrist3_Link"/>
<axis xyz="0 0 1"/>
<limit effort="28" lower="-6.28" upper="6.28" velocity="3.1416"/>
</joint>
<link name="world"/>
<joint name="world_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
<ros2_control name="aubo_hardware_interface" type="system">
<hardware>
<plugin>webots_ros2_control::Ros2ControlSystem</plugin>
</hardware>
<joint name="shoulder_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="upperArm_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="foreArm_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="wrist1_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="wrist2_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="wrist3_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
</ros2_control>
<webots>
<plugin type="webots_ros2_control::Ros2Control"/>
</webots>
</robot>

View file

@ -1,9 +1,4 @@
<?xml version="1.0"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from aubo_i5L.urdf | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="aubo_i5" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find aubo_description)/urdf/aubo.transmission.xacro" />
<xacro:include filename="$(find aubo_description)/urdf/materials.xacro" />
@ -243,19 +238,12 @@
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>
<!-- <xacro:dh_ag145_gripper prefix="" parent="wrist3_Link"> -->
<!-- <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> -->
<!-- </xacro:dh_ag145_gripper> -->
<xacro:simple_parallel_gripper prefix="" parent="wrist3_Link">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 1.57" />
</xacro:simple_parallel_gripper>
<xacro:rgbd parent="wrist3_Link" tf_prefix="">
<origin xyz="0.0 0.05 0.04" rpy="0.0 -1.47 -1.57" />
</xacro:rgbd>
<xacro:aubo_ros2_control hardware="${hardware}" robot_ip="${robot_ip}" />
<xacro:if value="${hardware=='webots'}">
<webots>
<plugin type="webots_ros2_control::Ros2Control"/>
</webots>
</xacro:if>
<xacro:if value="${hardware=='gazebo'}">
<gazebo>
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">

View file

@ -13,6 +13,9 @@
<plugin>aubo_driver/AuboHardwareInterface</plugin>
<param name="robot_ip">${robot_ip}</param>
</xacro:if>
<xacro:if value="${hardware=='webots'}">
<plugin>webots_ros2_control::Ros2ControlSystem</plugin>
</xacro:if>
</hardware>
<joint name="shoulder_joint">
@ -35,7 +38,7 @@
<param name="initial_value">0.5</param>
</state_interface>
</xacro:if>
<xacro:if value="${hardware=='real' or hardware=='mock'}">
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
<state_interface name="position" />
</xacro:if>
<state_interface name="velocity" />
@ -51,7 +54,7 @@
<param name="initial_value">1.75</param>
</state_interface>
</xacro:if>
<xacro:if value="${hardware=='real' or hardware=='mock'}">
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
<state_interface name="position" />
</xacro:if>
<state_interface name="velocity" />
@ -66,7 +69,7 @@
<param name="initial_value">0.0</param>
</state_interface>
</xacro:if>
<xacro:if value="${hardware=='real' or hardware=='mock'}">
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
<state_interface name="position" />
</xacro:if>
<state_interface name="velocity" />
@ -81,7 +84,7 @@
<param name="initial_value">1.57</param>
</state_interface>
</xacro:if>
<xacro:if value="${hardware=='real' or hardware=='mock'}">
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
<state_interface name="position" />
</xacro:if>
<state_interface name="velocity" />
@ -91,7 +94,7 @@
<command_interface name="position" />
<command_interface name="velocity" />
<xacro:if value="${hardware=='gazebo'}">
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>

View file

@ -1,4 +1,4 @@
simulation_controllers: !variable controllers_file
robot_ip: 192.168.0.106
hardware: gazebo
hardware: webots
with_gripper: "true"

49
world/aubo_robot.wbt Normal file
View file

@ -0,0 +1,49 @@
#VRML_SIM R2023b utf8
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/develop/projects/objects/backgrounds/protos/TexturedBackground.proto"
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/develop/projects/objects/floors/protos/Floor.proto"
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/develop/projects/appearances/protos/ThreadMetalPlate.proto"
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/develop/projects/objects/solids/protos/SolidBox.proto"
EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/develop/projects/appearances/protos/GalvanizedMetal.proto"
WorldInfo {
info [
"Aubo i5 Robot"
]
title "Aubo Robot"
basicTimeStep 16
physicsDisableAngularThreshold 0.1
contactProperties [
ContactProperties {
bounce 0.1
}
ContactProperties {
material1 "slope"
coulombFriction [
0.5
]
}
]
}
Viewpoint {
orientation 0.3118460054718159 0.06120895855528569 -0.9481590226664772 2.710827783218323
position 2.9308358456729615 1.1235070287382412 2.814381048353761
exposure 1.7
}
TexturedBackground {
texture "factory"
}
Floor {
size 20 20
appearance ThreadMetalPlate {
}
}
SolidBox {
translation 0 0 0.3
size 0.3 0.3 0.6
appearance GalvanizedMetal {
textureTransform TextureTransform {
scale 2 2
}
}
}