Migrate to Gazebo Fortress
This commit is contained in:
parent
b34c00a9b9
commit
e46c7bef74
113 changed files with 2751 additions and 25450 deletions
|
@ -6,7 +6,7 @@ This package consists of files describing the AQUA model of the robot, the entir
|
|||
.
|
||||
├── CMakeLists.txt
|
||||
├── config
|
||||
│ ├── rasmt_ros2_controllers.yaml # File describing the robot controllers
|
||||
│ ├── rasmt_effort_controllers.yaml # File describing the robot controllers
|
||||
│ └── rasmt.rviz
|
||||
├── launch
|
||||
│ ├── rasmt_control.launch.py # Launch file for running robot controlles
|
||||
|
|
80
rasmt_support/config/rasmt_effort_controllers.yaml
Normal file
80
rasmt_support/config/rasmt_effort_controllers.yaml
Normal file
|
@ -0,0 +1,80 @@
|
|||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 250
|
||||
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
||||
rasmt_arm_controller:
|
||||
type: effort_controllers/JointGroupEffortController
|
||||
|
||||
rasmt_hand_controller:
|
||||
type: effort_controllers/JointGroupEffortController
|
||||
|
||||
rasmt_arm_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- rasmt_Rot_Z_1
|
||||
- rasmt_Rot_Y_1
|
||||
- rasmt_Rot_Z_2
|
||||
- rasmt_Rot_Y_2
|
||||
- rasmt_Rot_Z_3
|
||||
- rasmt_Rot_Y_4
|
||||
command_interfaces:
|
||||
- effort
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
gains:
|
||||
rasmt_Rot_Z_1:
|
||||
p: 4000.0
|
||||
d: 10.0
|
||||
i: 250.0
|
||||
i_clamp: 15.0
|
||||
rasmt_Rot_Y_1:
|
||||
p: 10000.0
|
||||
d: 25.0
|
||||
i: 600.0
|
||||
i_clamp: 45.0
|
||||
rasmt_Rot_Z_2:
|
||||
p: 8000.0
|
||||
d: 20.0
|
||||
i: 450.0
|
||||
i_clamp: 30.0
|
||||
rasmt_Rot_Y_2:
|
||||
p: 6000.0
|
||||
d: 15.0
|
||||
i: 300.0
|
||||
i_clamp: 30.0
|
||||
rasmt_Rot_Z_3:
|
||||
p: 3000.0
|
||||
d: 5.0
|
||||
i: 175.0
|
||||
i_clamp: 7.0
|
||||
rasmt_Rot_Y_4:
|
||||
p: 2500.0
|
||||
d: 3.0
|
||||
i: 150.0
|
||||
i_clamp: 6.0
|
||||
|
||||
rasmt_hand_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- rasmt_Slide_1
|
||||
- rasmt_Slide_2
|
||||
command_interfaces:
|
||||
- effort
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
gains:
|
||||
rasmt_Slide_1:
|
||||
p: 225.0
|
||||
d: 0.001
|
||||
i: 0.4
|
||||
i_clamp: 4.0
|
||||
rasmt_Slide_2:
|
||||
p: 225.0
|
||||
d: 0.001
|
||||
i: 0.4
|
||||
i_clamp: 4.0
|
|
@ -6,7 +6,7 @@ controller_manager:
|
|||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
rasmt_hand_controller:
|
||||
type: forward_command_controller/ForwardCommandController
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
@ -14,11 +14,6 @@ controller_manager:
|
|||
|
||||
rasmt_arm_controller:
|
||||
ros__parameters:
|
||||
command_interfaces:
|
||||
- position
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
joints:
|
||||
- rasmt_Rot_Z_1
|
||||
- rasmt_Rot_Y_1
|
||||
|
@ -26,10 +21,19 @@ rasmt_arm_controller:
|
|||
- rasmt_Rot_Y_2
|
||||
- rasmt_Rot_Z_3
|
||||
- rasmt_Rot_Y_4
|
||||
command_interfaces:
|
||||
- position
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
|
||||
rasmt_hand_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
joints:
|
||||
- rasmt_Slide_1
|
||||
- rasmt_Slide_2
|
||||
interface_name: position
|
||||
command_interfaces:
|
||||
- position
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
|
@ -0,0 +1,41 @@
|
|||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 1000 # Hz
|
||||
|
||||
rasmt_arm_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
rasmt_hand_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
||||
|
||||
rasmt_arm_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- rasmt_Rot_Z_1
|
||||
- rasmt_Rot_Y_1
|
||||
- rasmt_Rot_Z_2
|
||||
- rasmt_Rot_Y_2
|
||||
- rasmt_Rot_Z_3
|
||||
- rasmt_Rot_Y_4
|
||||
command_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
|
||||
rasmt_hand_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- rasmt_Slide_1
|
||||
- rasmt_Slide_2
|
||||
command_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
|
@ -1,6 +1,7 @@
|
|||
from numpy import load
|
||||
from launch.launch_description import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.conditions import UnlessCondition
|
||||
from launch.actions import DeclareLaunchArgument, ExecuteProcess
|
||||
from launch.conditions import UnlessCondition, IfCondition
|
||||
from launch.substitutions import PathJoinSubstitution, LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
@ -27,22 +28,23 @@ def generate_launch_description():
|
|||
|
||||
# Configure robot_description
|
||||
robot_description = {"robot_description": LaunchConfiguration("robot_description")}
|
||||
|
||||
# Load controllers from YAML configuration file
|
||||
controller_configurations = PathJoinSubstitution([
|
||||
FindPackageShare("rasmt_support"),
|
||||
"config",
|
||||
"rasmt_ros2_controllers.yaml"
|
||||
"rasmt_position_velocity_controllers.yaml"
|
||||
])
|
||||
|
||||
# Prepare controller manager and other required nodes
|
||||
controller_manager = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
parameters=[robot_description, controller_configurations],
|
||||
output="screen",
|
||||
condition=UnlessCondition(LaunchConfiguration("sim"))
|
||||
)
|
||||
# ros2_control_node = Node(
|
||||
# package="controller_manager",
|
||||
# executable="ros2_control_node",
|
||||
# parameters=[robot_description, controller_configurations],
|
||||
# output={
|
||||
# "stdout": "screen",
|
||||
# "stderr": "screen",
|
||||
# },
|
||||
# )
|
||||
|
||||
robot_state_publisher = Node(
|
||||
package="robot_state_publisher",
|
||||
|
@ -51,33 +53,32 @@ def generate_launch_description():
|
|||
parameters=[robot_description]
|
||||
)
|
||||
|
||||
joint_state_broadcaster = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner.py",
|
||||
arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
|
||||
)
|
||||
# action_server_controller_hand_node = Node(
|
||||
# package="robossembler_servers",
|
||||
# executable="gripper_cmd_node"
|
||||
# )
|
||||
|
||||
|
||||
# Load controllers
|
||||
load_controllers = []
|
||||
for controller in [
|
||||
"rasmt_arm_controller",
|
||||
"rasmt_hand_controller",
|
||||
"joint_state_broadcaster",
|
||||
]:
|
||||
load_controllers += [
|
||||
ExecuteProcess(
|
||||
cmd=["ros2 control load_controller --set-state start {}".format(controller)],
|
||||
shell=True,
|
||||
output="screen",
|
||||
)
|
||||
]
|
||||
|
||||
controller_arm = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner.py",
|
||||
arguments=["rasmt_arm_controller", "--controller-manager", "/controller_manager"],
|
||||
)
|
||||
controller_hand = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner.py",
|
||||
arguments=["rasmt_hand_controller", "--controller-manager", "/controller_manager"],
|
||||
)
|
||||
action_server_controller_hand_node = Node(
|
||||
package="robossembler_servers",
|
||||
executable="gripper_cmd_node"
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
launch_args + [
|
||||
controller_manager,
|
||||
robot_state_publisher,
|
||||
joint_state_broadcaster,
|
||||
controller_arm,
|
||||
controller_hand,
|
||||
action_server_controller_hand_node
|
||||
])
|
||||
[
|
||||
robot_state_publisher
|
||||
]
|
||||
+ load_controllers
|
||||
+ launch_args
|
||||
)
|
||||
|
|
|
@ -21,22 +21,20 @@ def generate_launch_description():
|
|||
world_file = os.path.join(get_package_share_directory("rasmt_support"), "world", "robossembler.world")
|
||||
#test_world_file = "/home/bill-finger/gazebo_pkgs_ws/gazebo-pkgs/gazebo_grasp_plugin/test_world/test_world_full.world"
|
||||
|
||||
gzserver = IncludeLaunchDescription(
|
||||
# gzserver = IncludeLaunchDescription(
|
||||
# PythonLaunchDescriptionSource(
|
||||
# os.path.join(get_package_share_directory("gazebo_ros"), 'launch', 'gzserver.launch.py'),
|
||||
# ), launch_arguments={'world':world_file}.items()
|
||||
# )
|
||||
# gzclient = IncludeLaunchDescription(
|
||||
# PythonLaunchDescriptionSource(
|
||||
# os.path.join(get_package_share_directory("gazebo_ros"), 'launch', 'gzclient.launch.py'),
|
||||
# )
|
||||
# )
|
||||
|
||||
gazebo = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare("gazebo_ros"),
|
||||
"launch",
|
||||
"gzserver.launch.py"
|
||||
])
|
||||
), launch_arguments={'world':world_file, 'extra_gazebo_args':'--verbose'}.items()
|
||||
)
|
||||
gzclient = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare("gazebo_ros"),
|
||||
"launch",
|
||||
"gzclient.launch.py"
|
||||
])
|
||||
os.path.join(get_package_share_directory("gazebo_ros"), 'launch', 'gazebo.launch.py'),
|
||||
)
|
||||
)
|
||||
|
||||
|
@ -66,9 +64,9 @@ def generate_launch_description():
|
|||
)"""
|
||||
|
||||
launch_nodes = []
|
||||
#launch_nodes.append(gazebo)
|
||||
launch_nodes.append(gzserver)
|
||||
launch_nodes.append(gzclient)
|
||||
launch_nodes.append(gazebo)
|
||||
#launch_nodes.append(gzserver)
|
||||
#launch_nodes.append(gzclient)
|
||||
launch_nodes.append(spawn_entity)
|
||||
#launch_nodes.append(cube_spawn)
|
||||
|
||||
|
|
71
rasmt_support/launch/rasmt_ignition.launch.py
Normal file
71
rasmt_support/launch/rasmt_ignition.launch.py
Normal file
|
@ -0,0 +1,71 @@
|
|||
from launch import LaunchDescription
|
||||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
IncludeLaunchDescription,
|
||||
OpaqueFunction,
|
||||
RegisterEventHandler,
|
||||
)
|
||||
from launch.conditions import IfCondition, UnlessCondition
|
||||
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
|
||||
import xacro
|
||||
import os
|
||||
from ament_index_python import get_package_share_directory
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
launch_args = []
|
||||
launch_args.append(DeclareLaunchArgument(
|
||||
name="robot_name",
|
||||
default_value="rasmt",
|
||||
description="Set robot name in gazebo env"
|
||||
)
|
||||
)
|
||||
launch_args.append(DeclareLaunchArgument(
|
||||
name="robot_description_content",
|
||||
description="Robot XML file"
|
||||
)
|
||||
)
|
||||
|
||||
#robot_description_content = {"robot_description":LaunchConfiguration("robot_description_content")}
|
||||
robot_description_content = LaunchConfiguration("robot_description_content")
|
||||
# launch Ignition Gazebo
|
||||
pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo')
|
||||
gazebo = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')),
|
||||
launch_arguments={'ign_args': '-r empty.sdf'}.items(),
|
||||
)
|
||||
|
||||
ros2_ign_bridge = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("rasmt_support"),
|
||||
"launch",
|
||||
"rasmt_ignition_bridge.launch.py"
|
||||
]
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
# Spawn
|
||||
spawn = Node(package='ros_ign_gazebo', executable='create',
|
||||
arguments=[
|
||||
'-string', robot_description_content,
|
||||
'-name', 'rasmt',
|
||||
'-allow_renaming', 'true'],
|
||||
output='screen')
|
||||
|
||||
|
||||
launch_nodes = []
|
||||
launch_nodes.append(gazebo)
|
||||
launch_nodes.append(spawn)
|
||||
launch_nodes.append(ros2_ign_bridge)
|
||||
|
||||
|
||||
return LaunchDescription(launch_args + launch_nodes)
|
62
rasmt_support/launch/rasmt_ignition_bridge.launch.py
Normal file
62
rasmt_support/launch/rasmt_ignition_bridge.launch.py
Normal file
|
@ -0,0 +1,62 @@
|
|||
from launch.launch_description import LaunchDescription
|
||||
from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
|
||||
from launch.substitutions import PathJoinSubstitution, LaunchConfiguration, FindExecutable, Command
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch_ros.actions import Node
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
import xacro
|
||||
import os
|
||||
from ament_index_python import get_package_share_directory
|
||||
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default=True)
|
||||
log_level = LaunchConfiguration('log_level', default='fatal')
|
||||
|
||||
|
||||
launch_args = []
|
||||
launch_args.append(
|
||||
DeclareLaunchArgument(
|
||||
name='use_sim_time',
|
||||
default_value=use_sim_time,
|
||||
description="If true, use simulated clock"
|
||||
)
|
||||
)
|
||||
launch_args.append(
|
||||
DeclareLaunchArgument(
|
||||
name='log_level',
|
||||
default_value=log_level,
|
||||
description="Log level of all nodes launched by this script"
|
||||
)
|
||||
)
|
||||
|
||||
# JointTrajectory bridge for gripper (ROS2 -> IGN)
|
||||
joint_trajectory_controller_bridge = Node(package='ros_ign_bridge',
|
||||
executable='parameter_bridge',
|
||||
name='parameter_bridge_gripper_trajectory',
|
||||
output='screen',
|
||||
arguments=['/gripper_trajectory@trajectory_msgs/msg/JointTrajectory]ignition.msgs.JointTrajectory',
|
||||
'--ros-args', '--log-level', log_level],
|
||||
parameters=[{'use_sim_time': use_sim_time}])
|
||||
|
||||
# ros_ign_bridge (clock -> ROS 2)
|
||||
ros2_ign_clock_bridge = Node(
|
||||
package="ros_ign_bridge",
|
||||
executable="parameter_bridge",
|
||||
output="log",
|
||||
arguments=[
|
||||
"/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock",
|
||||
"--ros-args",
|
||||
"--log-level",
|
||||
log_level,
|
||||
],
|
||||
parameters=[{"use_sim_time": use_sim_time}],
|
||||
)
|
||||
|
||||
launch_nodes = []
|
||||
#launch_nodes.append(joint_trajectory_controller_bridge)
|
||||
launch_nodes.append(ros2_ign_clock_bridge)
|
||||
|
||||
return LaunchDescription(launch_nodes + launch_args)
|
|
@ -17,5 +17,8 @@
|
|||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
<!-- <gazebo_ros gazebo_plugin_path="lib"/>
|
||||
<gazebo_ros gazebo_model_path="${prefix}"/> -->
|
||||
<!-- <gazebo_ros gazebo_media_path="${prefix}"/> -->
|
||||
</export>
|
||||
</package>
|
89
rasmt_support/urdf/ras.sdf
Normal file
89
rasmt_support/urdf/ras.sdf
Normal file
|
@ -0,0 +1,89 @@
|
|||
<sdf version='1.9'>
|
||||
<world name='empty'>
|
||||
<physics name='1ms' type='ignored'>
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
<real_time_update_rate>1000</real_time_update_rate>
|
||||
</physics>
|
||||
<plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
|
||||
<plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
|
||||
<plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
|
||||
<plugin name='ignition::gazebo::systems::Contact' filename='ignition-gazebo-contact-system'/>
|
||||
<gravity>0 0 -9.8</gravity>
|
||||
<magnetic_field>5.5645e-6 22.8758e-6 -42.3884e-6</magnetic_field>
|
||||
<atmosphere type='adiabatic'/>
|
||||
<scene>
|
||||
<ambient>0.4 0.4 0.4 1.0</ambient>
|
||||
<background>.7 .7 .7 1</background>
|
||||
<shadows>true</shadows>
|
||||
</scene>
|
||||
<model name='ground_plane'>
|
||||
<static>1</static>
|
||||
<link name='link'>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
<bounce/>
|
||||
<contact/>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<mass>1</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<enable_wind>0</enable_wind>
|
||||
</link>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<self_collide>0</self_collide>
|
||||
</model>
|
||||
<light name='sun' type='directional'>
|
||||
<pose>0 0 10 0 -0 0</pose>
|
||||
<cast_shadows>1</cast_shadows>
|
||||
<intensity>1</intensity>
|
||||
<direction>-0.5 0.1 -0.9</direction>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
<attenuation>
|
||||
<range>1000</range>
|
||||
<linear>0.01</linear>
|
||||
<constant>0.9</constant>
|
||||
<quadratic>0.001</quadratic>
|
||||
</attenuation>
|
||||
<spot>
|
||||
<inner_angle>0</inner_angle>
|
||||
<outer_angle>0</outer_angle>
|
||||
<falloff>0</falloff>
|
||||
</spot>
|
||||
</light>
|
||||
</world>
|
||||
</sdf>
|
512
rasmt_support/urdf/rasmt.sdf
Normal file
512
rasmt_support/urdf/rasmt.sdf
Normal file
|
@ -0,0 +1,512 @@
|
|||
<sdf version='1.9'>
|
||||
<model name='rasmt'>
|
||||
<joint name='to_world' type='fixed'>
|
||||
<pose relative_to='__model__'>0 0 0 0 0 0</pose>
|
||||
<parent>world</parent>
|
||||
<child>rasmt_Base_Link</child>
|
||||
</joint>
|
||||
<link name='rasmt_Base_Link'>
|
||||
<pose relative_to='to_world'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>-0.0030651 -3.2739e-05 0.082353 0 0 0</pose>
|
||||
<mass>5.2929</mass>
|
||||
<inertia>
|
||||
<ixx>0.0076169</ixx>
|
||||
<ixy>1.0121e-05</ixy>
|
||||
<ixz>-0.00010622</ixz>
|
||||
<iyy>0.0076597</iyy>
|
||||
<iyz>6.511699999999999e-05</iyz>
|
||||
<izz>0.01165</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Base_Link_collision'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Base_Link.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Base_Link_visual'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Base_Link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
||||
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Rot_Z_1' type='revolute'>
|
||||
<pose relative_to='rasmt_Base_Link'>0 0 0.2533 3.141585307179587 0 0</pose>
|
||||
<parent>rasmt_Base_Link</parent>
|
||||
<child>rasmt_Fork_1</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.1416</lower>
|
||||
<upper>3.1416</upper>
|
||||
<effort>5.149</effort>
|
||||
<velocity>0.99903</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Fork_1'>
|
||||
<pose relative_to='rasmt_Rot_Z_1'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>0.043764 -0.0066984 -0.032285 0 0 0</pose>
|
||||
<mass>0.67797</mass>
|
||||
<inertia>
|
||||
<ixx>0.0014091</ixx>
|
||||
<ixy>-6.2674e-05</ixy>
|
||||
<ixz>0.00057897</ixz>
|
||||
<iyy>0.0017329</iyy>
|
||||
<iyz>4.7826e-05</iyz>
|
||||
<izz>0.0019056</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Fork_1_collision'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Fork_1.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Fork_1_visual'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Fork_1.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
||||
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Rot_Y_1' type='revolute'>
|
||||
<pose relative_to='rasmt_Fork_1'>0.1045 0 -0.0795 -3.141585307179587 0 0</pose>
|
||||
<parent>rasmt_Fork_1</parent>
|
||||
<child>rasmt_Link_1</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-1.5707</lower>
|
||||
<upper>2.2863</upper>
|
||||
<effort>5.149</effort>
|
||||
<velocity>0.99903</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Link_1'>
|
||||
<pose relative_to='rasmt_Rot_Y_1'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>-0.00042264 0 0.075171 0 0 0</pose>
|
||||
<mass>1.8959</mass>
|
||||
<inertia>
|
||||
<ixx>0.0029317</ixx>
|
||||
<ixy>-9.417e-06</ixy>
|
||||
<ixz>5.5248e-05</ixz>
|
||||
<iyy>0.0031666</iyy>
|
||||
<iyz>-9.3067e-05</iyz>
|
||||
<izz>0.0015477</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Link_1_collision'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Link_1.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Link_1_visual'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Link_1.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
||||
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Rot_Z_2' type='revolute'>
|
||||
<pose relative_to='rasmt_Link_1'>0 0 0.17502 0 0 0</pose>
|
||||
<parent>rasmt_Link_1</parent>
|
||||
<child>rasmt_Fork_2</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.1416</lower>
|
||||
<upper>3.1416</upper>
|
||||
<effort>5.149</effort>
|
||||
<velocity>0.99903</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Fork_2'>
|
||||
<pose relative_to='rasmt_Rot_Z_2'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>0.043764 0.0066984 0.032285 0 0 0</pose>
|
||||
<mass>0.67797</mass>
|
||||
<inertia>
|
||||
<ixx>0.0014091</ixx>
|
||||
<ixy>6.2674e-05</ixy>
|
||||
<ixz>-0.00057897</ixz>
|
||||
<iyy>0.0017329</iyy>
|
||||
<iyz>4.7826e-05</iyz>
|
||||
<izz>0.0019056</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Fork_2_collision'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Fork_2.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Fork_2_visual'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Fork_2.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
||||
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Rot_Y_2' type='revolute'>
|
||||
<pose relative_to='rasmt_Fork_2'>0.1045 0 0.0795 0 0 0</pose>
|
||||
<parent>rasmt_Fork_2</parent>
|
||||
<child>rasmt_Link_2</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-1.5707</lower>
|
||||
<upper>2.2863</upper>
|
||||
<effort>5.149</effort>
|
||||
<velocity>0.99903</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Link_2'>
|
||||
<pose relative_to='rasmt_Rot_Y_2'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>-0.00042264 0 0.075171 0 0 0</pose>
|
||||
<mass>1.8959</mass>
|
||||
<inertia>
|
||||
<ixx>0.0029317</ixx>
|
||||
<ixy>-9.4171e-06</ixy>
|
||||
<ixz>5.5248e-05</ixz>
|
||||
<iyy>0.0031666</iyy>
|
||||
<iyz>-9.3067e-05</iyz>
|
||||
<izz>0.0015477</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Link_2_collision'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Link_2.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Link_2_visual'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Link_2.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</diffuse>
|
||||
<ambient>0.9411749988794327 0.9411749988794327 0.9411749988794327 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Rot_Z_3' type='revolute'>
|
||||
<pose relative_to='rasmt_Link_2'>0 0 0.175 0 0 0</pose>
|
||||
<parent>rasmt_Link_2</parent>
|
||||
<child>rasmt_Fork_3</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-3.14159</lower>
|
||||
<upper>3.14159</upper>
|
||||
<effort>5.149</effort>
|
||||
<velocity>0.99903</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Fork_3'>
|
||||
<pose relative_to='rasmt_Rot_Z_3'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>0.0437644555284691 0.00669835350471771 0.0322846229336455 0 0 0</pose>
|
||||
<mass>0.677972982551887</mass>
|
||||
<inertia>
|
||||
<ixx>0.00140908677953665</ixx>
|
||||
<ixy>6.267434924451639e-05</ixy>
|
||||
<ixz>-0.000578970009504215</ixz>
|
||||
<iyy>0.00173285340301686</iyy>
|
||||
<iyz>4.78263030621606e-05</iyz>
|
||||
<izz>0.00190561919128035</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Fork_3_collision'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Fork_3.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Fork_3_visual'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Fork_3.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</diffuse>
|
||||
<ambient>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Rot_Y_4' type='revolute'>
|
||||
<pose relative_to='rasmt_Fork_3'>0.1045 0 0.0795 0 0 0</pose>
|
||||
<parent>rasmt_Fork_3</parent>
|
||||
<child>rasmt_Dock_Link</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-1.5707</lower>
|
||||
<upper>2.2863</upper>
|
||||
<effort>5.149</effort>
|
||||
<velocity>0.99903</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Dock_Link'>
|
||||
<pose relative_to='rasmt_Rot_Y_4'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>0.000487278098416338 0.0001516907797566372 0.08254557371325712 0 0 0</pose>
|
||||
<mass>2.53391750781824</mass>
|
||||
<inertia>
|
||||
<ixx>0.006064508328644976</ixx>
|
||||
<ixy>-2.015356731520154e-06</ixy>
|
||||
<ixz>-7.294101423638933e-05</ixz>
|
||||
<iyy>0.006094829365861896</iyy>
|
||||
<iyz>-0.0001246350455024134</iyz>
|
||||
<izz>0.002069011842474237</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Dock_Link_collision'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Dock_Link.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision name='rasmt_Dock_Link_fixed_joint_lump__rasmt_Grip_Body_collision_1'>
|
||||
<pose>0 0 0.12324 -3.14159265358979 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Grip_Body.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Dock_Link_visual'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Dock_Link.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</diffuse>
|
||||
<ambient>0.9411764889955521 0.9411764889955521 0.9411764889955521 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name='rasmt_Dock_Link_fixed_joint_lump__rasmt_Grip_Body_visual_1'>
|
||||
<pose>0 0 0.12324 -3.14159265358979 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Grip_Body.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.6274499744176865 1 0.6274499744176865 1</diffuse>
|
||||
<ambient>0.6274499744176865 1 0.6274499744176865 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Slide_1' type='prismatic'>
|
||||
<pose relative_to='rasmt_Dock_Link'>0 -3.006528453019044e-16 0.21629 7.346410206709656e-06 -3.231089339497412e-15 1.5708</pose>
|
||||
<parent>rasmt_Dock_Link</parent>
|
||||
<child>rasmt_Grip_L</child>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>0</lower>
|
||||
<upper>0.06</upper>
|
||||
<effort>20</effort>
|
||||
<velocity>0.2</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Grip_L'>
|
||||
<pose relative_to='rasmt_Slide_1'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>-0.010118 0.010281 -0.0038252 0 0 0</pose>
|
||||
<mass>0.021223</mass>
|
||||
<inertia>
|
||||
<ixx>6.5436e-06</ixx>
|
||||
<ixy>-3.114e-06</ixy>
|
||||
<ixz>2.8479e-06</ixz>
|
||||
<iyy>1.9726e-05</iyy>
|
||||
<iyz>1.6432e-06</iyz>
|
||||
<izz>1.6355e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Grip_L_collision'>
|
||||
<pose>-0.02 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Grip_L.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Grip_L_visual'>
|
||||
<pose>-0.02 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Grip_L.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411749988794327 1 1 1</diffuse>
|
||||
<ambient>0.9411749988794327 1 1 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='rasmt_Slide_2' type='prismatic'>
|
||||
<pose relative_to='rasmt_Dock_Link'>0 -3.006528453019044e-16 0.21629 7.346410206709656e-06 3.231089339497412e-15 -1.5708</pose>
|
||||
<parent>rasmt_Dock_Link</parent>
|
||||
<child>rasmt_Grip_R</child>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>0</lower>
|
||||
<upper>0.06</upper>
|
||||
<effort>20</effort>
|
||||
<velocity>0.2</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name='rasmt_Grip_R'>
|
||||
<pose relative_to='rasmt_Slide_2'>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>-0.010118 0.010281 -0.0038252 0 0 0</pose>
|
||||
<mass>0.021223</mass>
|
||||
<inertia>
|
||||
<ixx>6.5436e-06</ixx>
|
||||
<ixy>-3.114e-06</ixy>
|
||||
<ixz>2.8479e-06</ixz>
|
||||
<iyy>1.9726e-05</iyy>
|
||||
<iyz>1.6432e-06</iyz>
|
||||
<izz>1.6355e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rasmt_Grip_R_collision'>
|
||||
<pose>-0.02 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/collision/Grip_R.STL</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='rasmt_Grip_R_visual'>
|
||||
<pose>-0.02 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://rasmt_support/meshes/visual/Grip_R.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<diffuse>0.9411749988794327 1 1 1</diffuse>
|
||||
<ambient>0.9411749988794327 1 1 1</ambient>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<static>false</static>
|
||||
<plugin name='ign_ros2_control' filename='libign_ros2_control-system.so'>
|
||||
<parameters>/home/bill-finger/rasms_ws/install/share/rasmt_support/config/rasmt_effort_controllers.yaml</parameters>
|
||||
</plugin>
|
||||
</model>
|
||||
</sdf>
|
486
rasmt_support/urdf/rasmt.urdf
Normal file
486
rasmt_support/urdf/rasmt.urdf
Normal file
|
@ -0,0 +1,486 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from rasmt.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="rasmt">
|
||||
|
||||
<mujoco>
|
||||
<compiler balanceinertia="true" discardvisual="true" fusestatic="true" meshdir="../meshes_mjcf/" strippath="true"/>
|
||||
</mujoco>
|
||||
|
||||
|
||||
<link name="world"/>
|
||||
<joint name="to_world" type="fixed">
|
||||
<parent link="world"/>
|
||||
<child link="rasmt_Base_Link"/>
|
||||
<!--origin xyz="0 0 1.15" rpy="3.14159 0 3.14159"/-->
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="rasmt_Base_Link">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.0030651 -3.2739E-05 0.082353"/>
|
||||
<mass value="5.2929"/>
|
||||
<inertia ixx="0.0076169" ixy="1.0121E-05" ixz="-0.00010622" iyy="0.0076597" iyz="6.5117E-05" izz="0.01165"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Base_Link.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Base_Link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="rasmt_Fork_1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.043764 -0.0066984 -0.032285"/>
|
||||
<mass value="0.67797"/>
|
||||
<inertia ixx="0.0014091" ixy="-6.2674E-05" ixz="0.00057897" iyy="0.0017329" iyz="4.7826E-05" izz="0.0019056"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Fork_1.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Fork_1.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Rot_Z_1" type="revolute">
|
||||
<origin rpy="-3.1416 0 0" xyz="0 0 0.2533"/>
|
||||
<parent link="rasmt_Base_Link"/>
|
||||
<child link="rasmt_Fork_1"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="5.149" lower="-3.1416" upper="3.1416" velocity="0.99903"/>
|
||||
</joint>
|
||||
<link name="rasmt_Link_1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00042264 0.0 0.075171"/>
|
||||
<mass value="1.8959"/>
|
||||
<inertia ixx="0.0029317" ixy="-9.417E-06" ixz="5.5248E-05" iyy="0.0031666" iyz="-9.3067E-05" izz="0.0015477"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Link_1.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Link_1.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Rot_Y_1" type="revolute">
|
||||
<origin rpy="3.1416 0 0" xyz="0.1045 0.0 -0.0795"/>
|
||||
<parent link="rasmt_Fork_1"/>
|
||||
<child link="rasmt_Link_1"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="5.149" lower="-1.5707" upper="2.2863" velocity="0.99903"/>
|
||||
</joint>
|
||||
<link name="rasmt_Fork_2">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.043764 0.0066984 0.032285"/>
|
||||
<mass value="0.67797"/>
|
||||
<inertia ixx="0.0014091" ixy="6.2674E-05" ixz="-0.00057897" iyy="0.0017329" iyz="4.7826E-05" izz="0.0019056"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Fork_2.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Fork_2.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Rot_Z_2" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.0 0.17502"/>
|
||||
<parent link="rasmt_Link_1"/>
|
||||
<child link="rasmt_Fork_2"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="5.149" lower="-3.1416" upper="3.1416" velocity="0.99903"/>
|
||||
</joint>
|
||||
<link name="rasmt_Link_2">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00042264 0.0 0.075171"/>
|
||||
<mass value="1.8959"/>
|
||||
<inertia ixx="0.0029317" ixy="-9.4171E-06" ixz="5.5248E-05" iyy="0.0031666" iyz="-9.3067E-05" izz="0.0015477"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Link_2.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Link_2.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Rot_Y_2" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1045 0.0 0.0795"/>
|
||||
<parent link="rasmt_Fork_2"/>
|
||||
<child link="rasmt_Link_2"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="5.149" lower="-1.5707" upper="2.2863" velocity="0.99903"/>
|
||||
</joint>
|
||||
<link name="rasmt_Fork_3">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0437644555284691 0.00669835350471771 0.0322846229336455"/>
|
||||
<mass value="0.677972982551887"/>
|
||||
<inertia ixx="0.00140908677953665" ixy="6.26743492445164E-05" ixz="-0.000578970009504215" iyy="0.00173285340301686" iyz="4.78263030621606E-05" izz="0.00190561919128035"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Fork_3.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.752941176470588 0.752941176470588 0.752941176470588 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Fork_3.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Rot_Z_3" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.0 0.175"/>
|
||||
<parent link="rasmt_Link_2"/>
|
||||
<child link="rasmt_Fork_3"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="5.149" lower="-3.14159" upper="3.14159" velocity="0.99903"/>
|
||||
</joint>
|
||||
<link name="rasmt_Dock_Link">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="1.08992929317431E-05 0.0 0.0566747528784688"/>
|
||||
<mass value="1.81040750781824"/>
|
||||
<inertia ixx="0.00136087225665183" ixy="-1.57915998142718E-06" ixz="-1.31398366941724E-06" iyy="0.00136397029450427" iyz="-0.00010058418524025" izz="0.00124273705160787"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Dock_Link.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.752941176470588 0.752941176470588 0.752941176470588 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Dock_Link.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Rot_Y_4" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1045 0.0 0.0795"/>
|
||||
<parent link="rasmt_Fork_3"/>
|
||||
<child link="rasmt_Dock_Link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="5.149" lower="-1.5707" upper="2.2863" velocity="0.99903"/>
|
||||
</joint>
|
||||
<!-- ros_control-plugin -->
|
||||
<!-- <xacro:if value="${sim == 'gazebo'}">
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
|
||||
<parameters>$(find rasmt_support)/config/rasmt_effort_controllers.yaml</parameters>
|
||||
<robotNamespace>/${prefix}</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:if> -->
|
||||
<gazebo>
|
||||
<plugin filename="ign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
|
||||
<parameters>/home/bill-finger/rasms_ws/install/share/rasmt_support/config/rasmt_effort_controllers.yaml</parameters>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<!-- <gazebo reference="${prefix}_Base_Link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Fork_1">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Link_1">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Fork_2">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Link_2">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Fork_3">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Dock_Link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo> -->
|
||||
<!-- arg for control mode -->
|
||||
<ros2_control name="rasmt_single_hi" type="system">
|
||||
<hardware>
|
||||
<plugin>ign_ros2_control/IgnitionSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="rasmt_Rot_Z_1">
|
||||
<command_interface name="position">
|
||||
<!-- better to use radians as min max first -->
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
<joint name="rasmt_Rot_Y_1">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
<joint name="rasmt_Rot_Z_2">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
<joint name="rasmt_Rot_Y_2">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
<joint name="rasmt_Rot_Z_3">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
<joint name="rasmt_Rot_Y_4">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
</ros2_control>
|
||||
<link name="rasmt_tool0"/>
|
||||
<joint name="rasmt_tool0_fixed" type="fixed">
|
||||
<parent link="rasmt_Dock_Link"/>
|
||||
<child link="rasmt_tool0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.12324"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
<!--link name="${prefix}_tool_end_point"/>
|
||||
<joint name="${prefix}_tool_end_point_to_tool0" type="fixed">
|
||||
<parent link="${prefix}_Dock_Link"/>
|
||||
<child link="${prefix}_tool_end_point"/>
|
||||
<origin xyz="0 0 ${gripper_length+0.12324}" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint-->
|
||||
<link name="rasmt_Grip_Body">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0016793 -0.00053126 -0.024041"/>
|
||||
<mass value="0.72351"/>
|
||||
<inertia ixx="0.00045979" ixy="-2.1983E-08" ixz="-6.5154E-06" iyy="0.00048572" iyz="8.3162E-07" izz="0.00082469"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Grip_Body.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.50196 1 0.50196 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Grip_Body.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Fix" type="fixed">
|
||||
<origin rpy="-3.14159265358979 0 0" xyz="0 0.0 0.12324"/>
|
||||
<parent link="rasmt_Dock_Link"/>
|
||||
<child link="rasmt_Grip_Body"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="rasmt_Grip_L">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.010118 0.010281 -0.0038252"/>
|
||||
<mass value="0.021223"/>
|
||||
<inertia ixx="6.5436E-06" ixy="-3.114E-06" ixz="2.8479E-06" iyy="1.9726E-05" iyz="1.6432E-06" izz="1.6355E-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.02 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Grip_L.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="-0.02 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Grip_L.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Slide_1" type="prismatic">
|
||||
<origin rpy="3.1416 0 -1.5708" xyz="0 0 -0.09305"/>
|
||||
<parent link="rasmt_Grip_Body"/>
|
||||
<child link="rasmt_Grip_L"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="20" lower="0.0" upper="0.06" velocity="0.2"/>
|
||||
</joint>
|
||||
<link name="rasmt_Grip_R">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.010118 0.010281 -0.0038252"/>
|
||||
<mass value="0.021223"/>
|
||||
<inertia ixx="6.5436E-06" ixy="-3.114E-06" ixz="2.8479E-06" iyy="1.9726E-05" iyz="1.6432E-06" izz="1.6355E-05"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.02 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/visual/Grip_R.dae"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="-0.02 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://rasmt_support/meshes/collision/Grip_R.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rasmt_Slide_2" type="prismatic">
|
||||
<origin rpy="3.1416 0 1.5708" xyz="0 0 -0.09305"/>
|
||||
<parent link="rasmt_Grip_Body"/>
|
||||
<child link="rasmt_Grip_R"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="20" lower="0.0" upper="0.06" velocity="0.2"/>
|
||||
<!--mimic joint="${prefix}_Slide_1"/-->
|
||||
</joint>
|
||||
<!-- arg for control mode -->
|
||||
<ros2_control name="rasmt_hand_hi" type="system">
|
||||
<hardware>
|
||||
<plugin>ign_ros2_control/IgnitionSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="rasmt_Slide_1">
|
||||
<command_interface name="position">
|
||||
<!-- better to use radians as min max first -->
|
||||
<param name="min">0</param>
|
||||
<param name="max">10</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
<joint name="rasmt_Slide_2">
|
||||
<!-- <param name="mimic">${prefix}_Slide_1</param>
|
||||
<param name="multiplier">1</param> -->
|
||||
<command_interface name="position">
|
||||
<param name="min">0</param>
|
||||
<param name="max">10</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
</ros2_control>
|
||||
<!-- ros_control-plugin -->
|
||||
<!--gazebo>
|
||||
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
|
||||
<robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type>
|
||||
<parameters>$(find rasmt_support)/config/rasmt_hand_controllers.yaml</parameters>
|
||||
<robotNamespace>/${prefix}</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo-->
|
||||
<!-- <gazebo reference="${prefix}_Grip_Body">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Grip_L">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${prefix}_Grip_R">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo> -->
|
||||
</robot>
|
|
@ -1,21 +1,25 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="rasmt">
|
||||
|
||||
<xacro:arg name="grip" default="false"/>
|
||||
<xacro:arg name="sim" default="true"/>
|
||||
<xacro:arg name="grip" default="true"/>
|
||||
<xacro:arg name="sim" default="ignition"/>
|
||||
<xacro:arg name="robot_name" default="rasmt"/>
|
||||
|
||||
<xacro:include filename="$(find rasmt_support)/urdf/robot/rasmt_single_macro.xacro"/>
|
||||
<xacro:if value="$(arg grip)">
|
||||
<xacro:property name="gripper_length" value="0.12224"/>
|
||||
</xacro:if>
|
||||
|
||||
<link name="world"/>
|
||||
|
||||
<xacro:include filename="$(find rasmt_support)/urdf/robot/rasmt_single_macro.xacro"/>
|
||||
<xacro:rasmt_single prefix="$(arg robot_name)" parent="world" sim="$(arg sim)" xyz="0 0 0" gripper_length="${gripper_length}"/>
|
||||
<xacro:unless value="$(arg grip)">
|
||||
<xacro:rasmt_single prefix="$(arg robot_name)" parent="world" sim="$(arg sim)" xyz="0 0 0"/>
|
||||
</xacro:unless>
|
||||
|
||||
<!-- <xacro:rasmt_single prefix="$(arg robot_name)" parent="world" sim="$(arg sim)" xyz="0 0 0" gripper_length="${gripper_length}"/> -->
|
||||
|
||||
<xacro:if value="$(arg grip)">
|
||||
<xacro:include filename="$(find rasmt_support)/urdf/tools/rasmt_hand_macro.xacro"/>
|
||||
<xacro:rasmt_single prefix="$(arg robot_name)" parent="world" sim="$(arg sim)" xyz="0 0 0" gripper_length="${gripper_length}"/>
|
||||
<xacro:rasmt_hand prefix="$(arg robot_name)" sim="$(arg sim)"/>
|
||||
</xacro:if>
|
||||
|
||||
|
|
|
@ -4,74 +4,60 @@
|
|||
<!-- arg for control mode -->
|
||||
<ros2_control name="rasmt_single_hi" type="system">
|
||||
|
||||
<xacro:if value="${sim}">
|
||||
<!-- <xacro:if value="${sim == 'gazebo'}">
|
||||
<hardware>
|
||||
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
||||
</hardware>
|
||||
</xacro:if> -->
|
||||
<xacro:if value="${sim == 'ignition'}">
|
||||
<hardware>
|
||||
<plugin>ign_ros2_control/IgnitionSystem</plugin>
|
||||
</hardware>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:unless value="${sim}">
|
||||
<xacro:if value="${sim == 'fake'}">
|
||||
<hardware>
|
||||
<plugin>fake_components/GenericSystem</plugin>
|
||||
</hardware>
|
||||
</xacro:unless>
|
||||
</xacro:if>
|
||||
|
||||
<joint name="${prefix}_Rot_Z_1">
|
||||
<command_interface name="position">
|
||||
<!-- better to use radians as min max first -->
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${prefix}_Rot_Y_1">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${prefix}_Rot_Z_2">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${prefix}_Rot_Y_2">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${prefix}_Rot_Z_3">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${prefix}_Rot_Y_4">
|
||||
<command_interface name="position">
|
||||
<param name="min">-1</param>
|
||||
<param name="max"> 1</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
|
|
|
@ -1,63 +1,26 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:macro name="rasmt_single_gazebo" params="prefix">
|
||||
<xacro:macro name="rasmt_single_gazebo" params="prefix sim">
|
||||
|
||||
<!-- ros_control-plugin -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
|
||||
<!--robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type-->
|
||||
<parameters>$(find rasmt_support)/config/rasmt_ros2_controllers.yaml</parameters>
|
||||
<robotNamespace>/${prefix}</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<!-- <xacro:if value="${sim == 'gazebo'}">
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
|
||||
<parameters>$(find rasmt_support)/config/rasmt_position_velocity_controllers.yaml</parameters>
|
||||
<robotNamespace>/${prefix}</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:if> -->
|
||||
|
||||
<!-- link 0 -->
|
||||
<gazebo reference="${prefix}_Base_Link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
<xacro:if value="${sim == 'ignition'}">
|
||||
<gazebo reference="world"/>
|
||||
<gazebo>
|
||||
<plugin filename="ign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
|
||||
<parameters>$(find rasmt_support)/config/rasmt_effort_controllers.yaml</parameters>
|
||||
<!--controller_manager_node_name>controller_manager</controller_manager_node_name-->
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:if>
|
||||
|
||||
<!-- link 1 -->
|
||||
<gazebo reference="${prefix}_Fork_1">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<!-- link 2 -->
|
||||
<gazebo reference="${prefix}_Link_1">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<!-- link 3 -->
|
||||
<gazebo reference="${prefix}_Fork_2">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<!-- link 4 -->
|
||||
<gazebo reference="${prefix}_Link_2">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<!-- link 5 -->
|
||||
<gazebo reference="${prefix}_Fork_3">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<!-- link 6 -->
|
||||
<gazebo reference="${prefix}_Dock_Link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
</robot>
|
|
@ -398,7 +398,7 @@
|
|||
effort="5.149"
|
||||
velocity="0.99903" />
|
||||
</joint>
|
||||
<xacro:rasmt_single_gazebo prefix="${prefix}"/>
|
||||
<xacro:rasmt_single_gazebo prefix="${prefix}" sim="${sim}"/>
|
||||
<xacro:rasmt_single_control prefix="${prefix}" sim="${sim}"/>
|
||||
|
||||
<link name="${prefix}_tool0"/>
|
||||
|
|
|
@ -4,36 +4,32 @@
|
|||
<!-- arg for control mode -->
|
||||
<ros2_control name="rasmt_hand_hi" type="system">
|
||||
|
||||
<xacro:if value="${sim}">
|
||||
<xacro:if value="${sim == 'gazebo'}">
|
||||
<hardware>
|
||||
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
||||
</hardware>
|
||||
</xacro:if>
|
||||
<xacro:if value="${sim == 'ignition'}">
|
||||
<hardware>
|
||||
<plugin>ign_ros2_control/IgnitionSystem</plugin>
|
||||
</hardware>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:unless value="${sim}">
|
||||
<!-- <xacro:if value="${sim == 'fake'}">
|
||||
<hardware>
|
||||
<plugin>fake_components/GenericSystem</plugin>
|
||||
</hardware>
|
||||
</xacro:unless>
|
||||
</xacro:if> -->
|
||||
|
||||
<joint name="${prefix}_Slide_1">
|
||||
<command_interface name="position">
|
||||
<!-- better to use radians as min max first -->
|
||||
<param name="min">0</param>
|
||||
<param name="max">10</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${prefix}_Slide_2">
|
||||
<!-- <param name="mimic">${prefix}_Slide_1</param>
|
||||
<param name="multiplier">1</param> -->
|
||||
<command_interface name="position">
|
||||
<param name="min">0</param>
|
||||
<param name="max">10</param>
|
||||
</command_interface>
|
||||
<command_interface name="effort"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
|
|
|
@ -11,26 +11,23 @@
|
|||
</plugin>
|
||||
</gazebo-->
|
||||
|
||||
<!-- link 0 -->
|
||||
<gazebo reference="${prefix}_Grip_Body">
|
||||
<!-- <gazebo reference="${prefix}_Grip_Body">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<!-- link 1 -->
|
||||
<gazebo reference="${prefix}_Grip_L">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<!-- link 2 -->
|
||||
<gazebo reference="${prefix}_Grip_R">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<turnGravityOff>true</turnGravityOff>
|
||||
</gazebo>
|
||||
</gazebo> -->
|
||||
|
||||
</xacro:macro>
|
||||
</robot>
|
Loading…
Add table
Add a link
Reference in a new issue