Compare commits
3 commits
2-webots-i
...
main
Author | SHA1 | Date | |
---|---|---|---|
42721571fc | |||
5d162fbaec | |||
fb111da6bc |
10 changed files with 259 additions and 531 deletions
|
@ -3,7 +3,12 @@
|
||||||
gz_type_name: "gz.msgs.Clock"
|
gz_type_name: "gz.msgs.Clock"
|
||||||
direction: GZ_TO_ROS
|
direction: GZ_TO_ROS
|
||||||
|
|
||||||
- topic_name: "/rgbd_camera/image"
|
- topic_name: "/inner_rgbd_camera/image"
|
||||||
|
ros_type_name: "sensor_msgs/msg/Image"
|
||||||
|
gz_type_name: "gz.msgs.Image"
|
||||||
|
direction: GZ_TO_ROS
|
||||||
|
|
||||||
|
- topic_name: "/outer_rgbd_camera/image"
|
||||||
ros_type_name: "sensor_msgs/msg/Image"
|
ros_type_name: "sensor_msgs/msg/Image"
|
||||||
gz_type_name: "gz.msgs.Image"
|
gz_type_name: "gz.msgs.Image"
|
||||||
direction: GZ_TO_ROS
|
direction: GZ_TO_ROS
|
||||||
|
|
|
@ -1,131 +0,0 @@
|
||||||
#!/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())],
|
|
||||||
)
|
|
||||||
),
|
|
||||||
])
|
|
|
@ -1,55 +0,0 @@
|
||||||
#!/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())],
|
|
||||||
)
|
|
||||||
)
|
|
||||||
])
|
|
|
@ -1,275 +1,220 @@
|
||||||
<?xml version="1.0" ?>
|
<?xml version="1.0"?>
|
||||||
<!-- =================================================================================== -->
|
<robot name="aubo_i5">
|
||||||
<!-- | 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 | -->
|
<link name="base_link">
|
||||||
<!-- =================================================================================== -->
|
<inertial>
|
||||||
<robot name="aubo_i5">
|
<origin xyz="-1.4795E-13 0.0015384 0.020951" rpy="0 0 0" />
|
||||||
<material name="black">
|
<mass value="0.83419" />
|
||||||
<color rgba="0.25098 0.25098 0.25098 1"/>
|
<inertia ixx="0.0014414" ixy="7.8809E-15" ixz="8.5328E-16" iyy="0.0013542" iyz="-1.4364E-05" izz="0.0024659" />
|
||||||
</material>
|
</inertial>
|
||||||
<material name="orange">
|
<visual>
|
||||||
<color rgba="1.0 0.4235294117647059 0.0392156862745098 1.0"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</material>
|
<geometry>
|
||||||
<material name="white">
|
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/base_link.DAE" />
|
||||||
<color rgba="0.68627 0.69804 0.67451 1"/>
|
</geometry>
|
||||||
</material>
|
<material name="">
|
||||||
<material name="grey">
|
<color rgba="1 1 1 1" />
|
||||||
<color rgba="0.2 0.2 0.2 1.0"/>
|
</material>
|
||||||
</material>
|
</visual>
|
||||||
<material name="blue">
|
<collision>
|
||||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</material>
|
<geometry>
|
||||||
<material name="green">
|
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/base_link.STL" />
|
||||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
</geometry>
|
||||||
</material>
|
</collision>
|
||||||
<link name="base_link">
|
</link>
|
||||||
<inertial>
|
|
||||||
<origin rpy="0 0 0" xyz="-1.4795E-13 0.0015384 0.020951"/>
|
<link name="shoulder_Link">
|
||||||
<mass value="0.83419"/>
|
<inertial>
|
||||||
<inertia ixx="0.0014414" ixy="7.8809E-15" ixz="8.5328E-16" iyy="0.0013542" iyz="-1.4364E-05" izz="0.0024659"/>
|
<origin xyz="3.2508868974735E-07 0.00534955349296065 -0.00883689325611056" rpy="0 0 0" />
|
||||||
</inertial>
|
<mass value="1.57658348693929" />
|
||||||
<visual>
|
<inertia ixx="0.0040640448663128" ixy="0" ixz="0" iyy="0.00392863238466817" iyz="-0.000160151642851425" izz="0.0030869857349184" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
</inertial>
|
||||||
<geometry>
|
<visual>
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/base_link.DAE"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</geometry>
|
<geometry>
|
||||||
<material name="">
|
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/shoulder_Link.DAE" />
|
||||||
<color rgba="1 1 1 1"/>
|
</geometry>
|
||||||
</material>
|
<material name="">
|
||||||
</visual>
|
<color rgba="1 1 1 1" />
|
||||||
<collision>
|
</material>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
</visual>
|
||||||
<geometry>
|
<collision>
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/base_link.STL"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</geometry>
|
<geometry>
|
||||||
</collision>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/shoulder_Link.STL" />
|
||||||
</link>
|
</geometry>
|
||||||
<link name="shoulder_Link">
|
</collision>
|
||||||
<inertial>
|
</link>
|
||||||
<origin rpy="0 0 0" xyz="3.2508868974735E-07 0.00534955349296065 -0.00883689325611056"/>
|
|
||||||
<mass value="1.57658348693929"/>
|
<joint name="shoulder_joint" type="revolute">
|
||||||
<inertia ixx="0.0040640448663128" ixy="0" ixz="0" iyy="0.00392863238466817" iyz="-0.000160151642851425" izz="0.0030869857349184"/>
|
<origin xyz="0 0 0.122" rpy="0 0 3.1416" />
|
||||||
</inertial>
|
<parent link="base_link" />
|
||||||
<visual>
|
<child link="shoulder_Link" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<axis xyz="0 0 1" />
|
||||||
<geometry>
|
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/shoulder_Link.DAE"/>
|
</joint>
|
||||||
</geometry>
|
|
||||||
<material name="">
|
<link name="upperArm_Link">
|
||||||
<color rgba="1 1 1 1"/>
|
<inertial>
|
||||||
</material>
|
<origin xyz="0.203996646979614 2.01304585036544E-10 0.0127641545395984" rpy="0 0 0" />
|
||||||
</visual>
|
<mass value="4.04175782265494" />
|
||||||
<collision>
|
<inertia ixx="0.00965399211106204" ixy="0" ixz="0" iyy="0.144993869035655" iyz="0" izz="0.142607184038966" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
</inertial>
|
||||||
<geometry>
|
<visual>
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/shoulder_Link.STL"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</geometry>
|
<geometry>
|
||||||
</collision>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/upperArm_Link.DAE" />
|
||||||
</link>
|
</geometry>
|
||||||
<joint name="shoulder_joint" type="revolute">
|
<material name="">
|
||||||
<origin rpy="0 0 3.1416" xyz="0 0 0.122"/>
|
<color rgba="1 1 1 1" />
|
||||||
<parent link="base_link"/>
|
</material>
|
||||||
<child link="shoulder_Link"/>
|
</visual>
|
||||||
<axis xyz="0 0 1"/>
|
<collision>
|
||||||
<limit effort="150" lower="-6.28" upper="6.28" velocity="3.1416"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</joint>
|
<geometry>
|
||||||
<link name="upperArm_Link">
|
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/upperArm_Link.STL" />
|
||||||
<inertial>
|
</geometry>
|
||||||
<origin rpy="0 0 0" xyz="0.203996646979614 2.01304585036544E-10 0.0127641545395984"/>
|
</collision>
|
||||||
<mass value="4.04175782265494"/>
|
</link>
|
||||||
<inertia ixx="0.00965399211106204" ixy="0" ixz="0" iyy="0.144993869035655" iyz="0" izz="0.142607184038966"/>
|
|
||||||
</inertial>
|
<joint name="upperArm_joint" type="revolute">
|
||||||
<visual>
|
<origin xyz="0 0.1215 0" rpy="-1.5708 -1.5708 0" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<parent link="shoulder_Link" />
|
||||||
<geometry>
|
<child link="upperArm_Link" />
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/upperArm_Link.DAE"/>
|
<axis xyz="0 0 1" />
|
||||||
</geometry>
|
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
|
||||||
<material name="">
|
</joint>
|
||||||
<color rgba="1 1 1 1"/>
|
|
||||||
</material>
|
<link name="foreArm_Link">
|
||||||
</visual>
|
<inertial>
|
||||||
<collision>
|
<origin xyz="0.188922115560337 6.78882434739072E-07 0.0981026740461557" rpy="0 0 0" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<mass value="2.27145669098343" />
|
||||||
<geometry>
|
<inertia ixx="0.00214322284946289" ixy="0" ixz="-0.00073120631553383" iyy="0.0443926090878205" iyz="0" izz="0.0441273797128365" />
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/upperArm_Link.STL"/>
|
</inertial>
|
||||||
</geometry>
|
<visual>
|
||||||
</collision>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</link>
|
<geometry>
|
||||||
<joint name="upperArm_joint" type="revolute">
|
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/foreArm_Link.DAE" />
|
||||||
<origin rpy="-1.5708 -1.5708 0" xyz="0 0.1215 0"/>
|
</geometry>
|
||||||
<parent link="shoulder_Link"/>
|
<material name="">
|
||||||
<child link="upperArm_Link"/>
|
<color rgba="1 1 1 1" />
|
||||||
<axis xyz="0 0 1"/>
|
</material>
|
||||||
<limit effort="150" lower="-6.28" upper="6.28" velocity="3.1416"/>
|
</visual>
|
||||||
</joint>
|
<collision>
|
||||||
<link name="foreArm_Link">
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<inertial>
|
<geometry>
|
||||||
<origin rpy="0 0 0" xyz="0.188922115560337 6.78882434739072E-07 0.0981026740461557"/>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/foreArm_Link.STL" />
|
||||||
<mass value="2.27145669098343"/>
|
</geometry>
|
||||||
<inertia ixx="0.00214322284946289" ixy="0" ixz="-0.00073120631553383" iyy="0.0443926090878205" iyz="0" izz="0.0441273797128365"/>
|
</collision>
|
||||||
</inertial>
|
</link>
|
||||||
<visual>
|
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<joint name="foreArm_joint" type="revolute">
|
||||||
<geometry>
|
<origin xyz="0.408 0 0" rpy="-3.1416 -5.1632E-18 -5.459E-16" />
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/foreArm_Link.DAE"/>
|
<parent link="upperArm_Link" />
|
||||||
</geometry>
|
<child link="foreArm_Link" />
|
||||||
<material name="">
|
<axis xyz="0 0 1" />
|
||||||
<color rgba="1 1 1 1"/>
|
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
|
||||||
</material>
|
</joint>
|
||||||
</visual>
|
|
||||||
<collision>
|
<link name="wrist1_Link">
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<inertial>
|
||||||
<geometry>
|
<origin xyz="7.54205137428592E-07 0.0062481254331257 -0.00392367464072373" rpy="0 0 0" />
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/foreArm_Link.STL"/>
|
<mass value="0.500477539188764" />
|
||||||
</geometry>
|
<inertia ixx="0.00071194605962081" ixy="0" ixz="0" iyy="0.00040588242872958" iyz="-2.30808694377512E-05" izz="0.000685574004861334" />
|
||||||
</collision>
|
</inertial>
|
||||||
</link>
|
<visual>
|
||||||
<joint name="foreArm_joint" type="revolute">
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<origin rpy="-3.1416 -5.1632E-18 -5.459E-16" xyz="0.408 0 0"/>
|
<geometry>
|
||||||
<parent link="upperArm_Link"/>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist1_Link.DAE" />
|
||||||
<child link="foreArm_Link"/>
|
</geometry>
|
||||||
<axis xyz="0 0 1"/>
|
<material name="">
|
||||||
<limit effort="150" lower="-6.28" upper="6.28" velocity="3.1416"/>
|
<color rgba="1 1 1 1" />
|
||||||
</joint>
|
</material>
|
||||||
<link name="wrist1_Link">
|
</visual>
|
||||||
<inertial>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="7.54205137428592E-07 0.0062481254331257 -0.00392367464072373"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<mass value="0.500477539188764"/>
|
<geometry>
|
||||||
<inertia ixx="0.00071194605962081" ixy="0" ixz="0" iyy="0.00040588242872958" iyz="-2.30808694377512E-05" izz="0.000685574004861334"/>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist1_Link.STL" />
|
||||||
</inertial>
|
</geometry>
|
||||||
<visual>
|
</collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
</link>
|
||||||
<geometry>
|
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist1_Link.DAE"/>
|
<joint name="wrist1_joint" type="revolute">
|
||||||
</geometry>
|
<origin xyz="0.376 0 0" rpy="3.1416 -1.8323E-15 1.5708" />
|
||||||
<material name="">
|
<parent link="foreArm_Link" />
|
||||||
<color rgba="1 1 1 1"/>
|
<child link="wrist1_Link" />
|
||||||
</material>
|
<axis xyz="0 0 1" />
|
||||||
</visual>
|
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
|
||||||
<collision>
|
</joint>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
||||||
<geometry>
|
<link name="wrist2_Link">
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist1_Link.STL"/>
|
<inertial>
|
||||||
</geometry>
|
<origin xyz="-7.54207620578635E-07 -0.00624812542617262 -0.00392367464115684" rpy="0 0 0" />
|
||||||
</collision>
|
<mass value="0.500477539245988" />
|
||||||
</link>
|
<inertia ixx="0.00071194605981829" ixy="0" ixz="0" iyy="0.000405882428755442" iyz="2.30808694515886E-05" izz="0.000685574005112107" />
|
||||||
<joint name="wrist1_joint" type="revolute">
|
</inertial>
|
||||||
<origin rpy="3.1416 -1.8323E-15 1.5708" xyz="0.376 0 0"/>
|
<visual>
|
||||||
<parent link="foreArm_Link"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<child link="wrist1_Link"/>
|
<geometry>
|
||||||
<axis xyz="0 0 1"/>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist2_Link.DAE" />
|
||||||
<limit effort="28" lower="-6.28" upper="6.28" velocity="3.1416"/>
|
</geometry>
|
||||||
</joint>
|
<material name="">
|
||||||
<link name="wrist2_Link">
|
<color rgba="1 1 1 1" />
|
||||||
<inertial>
|
</material>
|
||||||
<origin rpy="0 0 0" xyz="-7.54207620578635E-07 -0.00624812542617262 -0.00392367464115684"/>
|
</visual>
|
||||||
<mass value="0.500477539245988"/>
|
<collision>
|
||||||
<inertia ixx="0.00071194605981829" ixy="0" ixz="0" iyy="0.000405882428755442" iyz="2.30808694515886E-05" izz="0.000685574005112107"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
</inertial>
|
<geometry>
|
||||||
<visual>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist2_Link.STL" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
</geometry>
|
||||||
<geometry>
|
</collision>
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist2_Link.DAE"/>
|
</link>
|
||||||
</geometry>
|
|
||||||
<material name="">
|
<joint name="wrist2_joint" type="revolute">
|
||||||
<color rgba="1 1 1 1"/>
|
<origin xyz="0 0.1025 0" rpy="-1.5708 -1.8709E-15 -1.6653E-16" />
|
||||||
</material>
|
<parent link="wrist1_Link" />
|
||||||
</visual>
|
<child link="wrist2_Link" />
|
||||||
<collision>
|
<axis xyz="0 0 1" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
|
||||||
<geometry>
|
</joint>
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist2_Link.STL"/>
|
|
||||||
</geometry>
|
<link name="wrist3_Link">
|
||||||
</collision>
|
<inertial>
|
||||||
</link>
|
<origin xyz="3.92048778449938E-10 0.000175788057281467 -0.0213294490706684" rpy="0 0 0" />
|
||||||
<joint name="wrist2_joint" type="revolute">
|
<mass value="0.158309554874285" />
|
||||||
<origin rpy="-1.5708 -1.8709E-15 -1.6653E-16" xyz="0 0.1025 0"/>
|
<inertia ixx="7.31376196034769E-05" ixy="0" ixz="0" iyy="7.19528188876563E-05" iyz="0" izz="0.000108772439051422" />
|
||||||
<parent link="wrist1_Link"/>
|
</inertial>
|
||||||
<child link="wrist2_Link"/>
|
<visual>
|
||||||
<axis xyz="0 0 1"/>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<limit effort="28" lower="-6.28" upper="6.28" velocity="3.1416"/>
|
<geometry>
|
||||||
</joint>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist3_Link.DAE" />
|
||||||
<link name="wrist3_Link">
|
</geometry>
|
||||||
<inertial>
|
<material name="">
|
||||||
<origin rpy="0 0 0" xyz="3.92048778449938E-10 0.000175788057281467 -0.0213294490706684"/>
|
<color rgba="1 1 1 1" />
|
||||||
<mass value="0.158309554874285"/>
|
</material>
|
||||||
<inertia ixx="7.31376196034769E-05" ixy="0" ixz="0" iyy="7.19528188876563E-05" iyz="0" izz="0.000108772439051422"/>
|
</visual>
|
||||||
</inertial>
|
<collision>
|
||||||
<visual>
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<geometry>
|
||||||
<geometry>
|
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist3_Link.STL" />
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/visual/wrist3_Link.DAE"/>
|
</geometry>
|
||||||
</geometry>
|
</collision>
|
||||||
<material name="">
|
</link>
|
||||||
<color rgba="1 1 1 1"/>
|
|
||||||
</material>
|
<joint name="wrist3_joint" type="revolute">
|
||||||
</visual>
|
<origin xyz="0 -0.094 0" rpy="1.5708 0 1.7907E-15" />
|
||||||
<collision>
|
<parent link="wrist2_Link" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<child link="wrist3_Link" />
|
||||||
<geometry>
|
<axis xyz="0 0 1" />
|
||||||
<mesh filename="package://aubo_description/meshes/aubo_i5/collision/wrist3_Link.STL"/>
|
<limit lower="-3.04" upper="3.04" effort="0" velocity="0" />
|
||||||
</geometry>
|
</joint>
|
||||||
</collision>
|
|
||||||
</link>
|
<link name="world" />
|
||||||
<joint name="wrist3_joint" type="revolute">
|
|
||||||
<origin rpy="1.5708 0 1.7907E-15" xyz="0 -0.094 0"/>
|
<joint name="world_joint" type="fixed">
|
||||||
<parent link="wrist2_Link"/>
|
<parent link="world" />
|
||||||
<child link="wrist3_Link"/>
|
<child link = "base_link" />
|
||||||
<axis xyz="0 0 1"/>
|
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||||
<limit effort="28" lower="-6.28" upper="6.28" velocity="3.1416"/>
|
</joint>
|
||||||
</joint>
|
</robot>
|
||||||
<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>
|
|
||||||
|
|
|
@ -1,4 +1,9 @@
|
||||||
<?xml version="1.0"?>
|
<?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">
|
<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/aubo.transmission.xacro" />
|
||||||
<xacro:include filename="$(find aubo_description)/urdf/materials.xacro" />
|
<xacro:include filename="$(find aubo_description)/urdf/materials.xacro" />
|
||||||
|
@ -238,12 +243,23 @@
|
||||||
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||||
</joint>
|
</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="inner_">
|
||||||
|
<origin xyz="0.0 0.05 0.0" rpy="0.0 -1.47 -1.57" />
|
||||||
|
</xacro:rgbd>
|
||||||
|
|
||||||
|
<xacro:rgbd parent="base_link" tf_prefix="outer_">
|
||||||
|
<origin xyz="0.62179261445999146 -0.83430188894271851 0.85204130411148071" rpy="0.00 0.608 1.934" />
|
||||||
|
</xacro:rgbd>
|
||||||
|
|
||||||
<xacro:aubo_ros2_control hardware="${hardware}" robot_ip="${robot_ip}" />
|
<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'}">
|
<xacro:if value="${hardware=='gazebo'}">
|
||||||
<gazebo>
|
<gazebo>
|
||||||
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
|
||||||
|
|
|
@ -13,9 +13,6 @@
|
||||||
<plugin>aubo_driver/AuboHardwareInterface</plugin>
|
<plugin>aubo_driver/AuboHardwareInterface</plugin>
|
||||||
<param name="robot_ip">${robot_ip}</param>
|
<param name="robot_ip">${robot_ip}</param>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${hardware=='webots'}">
|
|
||||||
<plugin>webots_ros2_control::Ros2ControlSystem</plugin>
|
|
||||||
</xacro:if>
|
|
||||||
</hardware>
|
</hardware>
|
||||||
|
|
||||||
<joint name="shoulder_joint">
|
<joint name="shoulder_joint">
|
||||||
|
@ -38,7 +35,7 @@
|
||||||
<param name="initial_value">0.5</param>
|
<param name="initial_value">0.5</param>
|
||||||
</state_interface>
|
</state_interface>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
|
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||||
<state_interface name="position" />
|
<state_interface name="position" />
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<state_interface name="velocity" />
|
<state_interface name="velocity" />
|
||||||
|
@ -54,7 +51,7 @@
|
||||||
<param name="initial_value">1.75</param>
|
<param name="initial_value">1.75</param>
|
||||||
</state_interface>
|
</state_interface>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
|
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||||
<state_interface name="position" />
|
<state_interface name="position" />
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<state_interface name="velocity" />
|
<state_interface name="velocity" />
|
||||||
|
@ -69,7 +66,7 @@
|
||||||
<param name="initial_value">0.0</param>
|
<param name="initial_value">0.0</param>
|
||||||
</state_interface>
|
</state_interface>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
|
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||||
<state_interface name="position" />
|
<state_interface name="position" />
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<state_interface name="velocity" />
|
<state_interface name="velocity" />
|
||||||
|
@ -84,7 +81,7 @@
|
||||||
<param name="initial_value">1.57</param>
|
<param name="initial_value">1.57</param>
|
||||||
</state_interface>
|
</state_interface>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
|
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||||
<state_interface name="position" />
|
<state_interface name="position" />
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<state_interface name="velocity" />
|
<state_interface name="velocity" />
|
||||||
|
@ -94,7 +91,7 @@
|
||||||
<command_interface name="position" />
|
<command_interface name="position" />
|
||||||
<command_interface name="velocity" />
|
<command_interface name="velocity" />
|
||||||
|
|
||||||
<xacro:if value="${hardware=='real' or hardware=='mock' or hardware=='webots'}">
|
<xacro:if value="${hardware=='gazebo'}">
|
||||||
<state_interface name="position">
|
<state_interface name="position">
|
||||||
<param name="initial_value">0.0</param>
|
<param name="initial_value">0.0</param>
|
||||||
</state_interface>
|
</state_interface>
|
||||||
|
|
|
@ -30,8 +30,8 @@
|
||||||
<camera>
|
<camera>
|
||||||
<horizontal_fov>1.047</horizontal_fov>
|
<horizontal_fov>1.047</horizontal_fov>
|
||||||
<image>
|
<image>
|
||||||
<width>1920</width>
|
<width>640</width>
|
||||||
<height>1080</height>
|
<height>480</height>
|
||||||
</image>
|
</image>
|
||||||
<clip>
|
<clip>
|
||||||
<near>0.1</near>
|
<near>0.1</near>
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
simulation_controllers: !variable controllers_file
|
simulation_controllers: !variable controllers_file
|
||||||
robot_ip: 192.168.0.106
|
robot_ip: 192.168.0.106
|
||||||
hardware: webots
|
hardware: gazebo
|
||||||
with_gripper: "true"
|
with_gripper: "true"
|
||||||
|
|
|
@ -1,49 +0,0 @@
|
||||||
#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
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
|
@ -110,8 +110,8 @@
|
||||||
<collision name="cylinder_collision">
|
<collision name="cylinder_collision">
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder>
|
<cylinder>
|
||||||
<radius>0.03</radius>
|
<radius>0.01</radius>
|
||||||
<length>0.1</length>
|
<length>0.05</length>
|
||||||
</cylinder>
|
</cylinder>
|
||||||
</geometry>
|
</geometry>
|
||||||
<surface>
|
<surface>
|
||||||
|
@ -133,8 +133,8 @@
|
||||||
<visual name="cylinder_visual">
|
<visual name="cylinder_visual">
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder>
|
<cylinder>
|
||||||
<radius>0.03</radius>
|
<radius>0.01</radius>
|
||||||
<length>0.1</length>
|
<length>0.05</length>
|
||||||
</cylinder>
|
</cylinder>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material>
|
<material>
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue