moveit config

This commit is contained in:
Ilya Uraev 2024-02-08 15:08:35 +03:00
parent bd48613598
commit 531e088525
12 changed files with 1095 additions and 0 deletions

View file

@ -0,0 +1,9 @@
# Default initial positions for rbs_arm's ros2_control fake system
initial_positions:
ee_link_joint: 0
fork0_link_joint: 0
fork1_link_joint: 0
fork2_link_joint: 0
main0_link_joint: 0
main1_link_joint: 0

View file

@ -0,0 +1,40 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
ee_link_joint:
has_velocity_limits: true
max_velocity: 0.52000000000000002
has_acceleration_limits: false
max_acceleration: 0
fork0_link_joint:
has_velocity_limits: true
max_velocity: 0.52000000000000002
has_acceleration_limits: false
max_acceleration: 0
fork1_link_joint:
has_velocity_limits: true
max_velocity: 0.52000000000000002
has_acceleration_limits: false
max_acceleration: 0
fork2_link_joint:
has_velocity_limits: true
max_velocity: 0.52000000000000002
has_acceleration_limits: false
max_acceleration: 0
main0_link_joint:
has_velocity_limits: true
max_velocity: 0.52000000000000002
has_acceleration_limits: false
max_acceleration: 0
main1_link_joint:
has_velocity_limits: true
max_velocity: 0.52000000000000002
has_acceleration_limits: false
max_acceleration: 0

View file

@ -0,0 +1,7 @@
/**:
ros__parameters:
robot_description_kinematics:
rbs_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001

View file

@ -0,0 +1,17 @@
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
moveit_simple_controller_manager:
controller_names:
- joint_trajectory_controller
joint_trajectory_controller:
type: FollowJointTrajectory
action_ns: follow_joint_trajectory
default: true
joints:
- fork0_link_joint
- main0_link_joint
- fork1_link_joint
- main1_link_joint
- fork2_link_joint
- ee_link_joint

View file

@ -0,0 +1,54 @@
planner_configs:
SBLkConfigDefault:
type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
ESTkConfigDefault:
type: geometric::EST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
LBKPIECEkConfigDefault:
type: geometric::LBKPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
BKPIECEkConfigDefault:
type: geometric::BKPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
KPIECEkConfigDefault:
type: geometric::KPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
RRTkConfigDefault:
type: geometric::RRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
RRTConnectkConfigDefault:
type: geometric::RRTConnect
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
RRTstarkConfigDefault:
type: geometric::RRTstar
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
TRRTkConfigDefault:
type: geometric::TRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
max_states_failed: 10 # when to start increasing temp. default: 10
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
init_temperature: 10e-6 # initial temperature. default: 10e-6
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup()
PRMkConfigDefault:
type: geometric::PRM
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
PRMstarkConfigDefault:
type: geometric::PRMstar

View file

@ -0,0 +1,6 @@
# Limits for the Pilz planner
cartesian_limits:
max_trans_vel: 1.0
max_trans_acc: 2.25
max_trans_dec: -5.0
max_rot_vel: 1.57

View file

@ -0,0 +1,10 @@
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="$(arg name)">
<xacro:arg name="name" default="rbs_arm" />
<xacro:arg name="prefix" default="" />
<xacro:include filename="$(find rbs_arm)/config/moveit/rbs_arm_macro.srdf.xacro" />
<xacro:rbs_arm name="$(arg name)" prefix="$(arg prefix)" />
</robot>

View file

@ -0,0 +1,35 @@
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="rbs_arm" params="prefix name">
<group name="${name}">
<joint name="${prefix}fork0_link_joint" />
<joint name="${prefix}main0_link_joint" />
<joint name="${prefix}fork1_link_joint" />
<joint name="${prefix}main1_link_joint" />
<joint name="${prefix}fork2_link_joint" />
<joint name="${prefix}ee_link_joint" />
<joint name="${prefix}tool0_joint" />
</group>
<group_state name="home" group="rbs_arm">
<joint name="${prefix}ee_link_joint" value="0" />
<joint name="${prefix}fork0_link_joint" value="0" />
<joint name="${prefix}fork1_link_joint" value="0" />
<joint name="${prefix}fork2_link_joint" value="0" />
<joint name="${prefix}main0_link_joint" value="0" />
<joint name="${prefix}main1_link_joint" value="0" />
</group_state>
<disable_collisions link1="${prefix}base_link" link2="${prefix}fork0_link" reason="Adjacent" />
<disable_collisions link1="${prefix}ee_link" link2="${prefix}fork2_link" reason="Adjacent" />
<disable_collisions link1="${prefix}fork0_link" link2="${prefix}fork1_link" reason="Never" />
<disable_collisions link1="${prefix}fork0_link" link2="${prefix}main0_link"
reason="Adjacent" />
<disable_collisions link1="${prefix}fork1_link" link2="${prefix}fork2_link" reason="Never" />
<disable_collisions link1="${prefix}fork1_link" link2="${prefix}main0_link"
reason="Adjacent" />
<disable_collisions link1="${prefix}fork1_link" link2="${prefix}main1_link"
reason="Adjacent" />
<disable_collisions link1="${prefix}fork2_link" link2="${prefix}main1_link"
reason="Adjacent" />
</xacro:macro>
</robot>

View file

@ -0,0 +1,142 @@
from launch_ros.actions import Node
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch.conditions import IfCondition, UnlessCondition
def generate_launch_description():
declared_arguments = []
declared_arguments.append(
DeclareLaunchArgument(
"with_gripper",
default_value="false",
description="With gripper or not?",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"robot_description",
default_value="",
description="robot description param",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"start_joint_controller",
default_value="false",
description="Enable headless mode for robot control",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"initial_joint_controller",
default_value="joint_trajectory_controller",
description="Robot controller to start.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"controllers_file",
default_value="rbs_arm_gazebosim.yaml",
description="YAML file with the controllers configuration.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"cartesian_controllers",
default_value="true",
description="Launch cartesian controllres",
)
)
robot_description_content = LaunchConfiguration("robot_description")
controllers_file = LaunchConfiguration("controllers_file")
start_joint_controller = LaunchConfiguration("start_joint_controller")
with_gripper_condition = LaunchConfiguration("with_gripper")
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
cartesian_controllers = LaunchConfiguration("cartesian_controllers")
initial_joint_controllers_file_path = PathJoinSubstitution(
[FindPackageShare("rba_arm"), "config", controllers_file]
)
robot_description = {"robot_description": robot_description_content}
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, initial_joint_controllers_file_path],
output="both",
remappings=[
('motion_control_handle/target_frame', 'target_frame'),
('cartesian_compliance_controller/target_frame', 'target_frame'),
('cartesian_compliance_controller/target_wrench', 'target_wrench'),
('cartesian_compliance_controller/ft_sensor_wrench', 'ft_sensor_wrench')],
condition=IfCondition(cartesian_controllers)
)
joint_state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster", "-c", "/controller_manager"],
)
# FIXME: Start controllers one controller by one launch or launch it all and switch by runtime?
initial_joint_controller_spawner_started = Node(
package="controller_manager",
executable="spawner",
arguments=[initial_joint_controller, "-c", "/controller_manager"],
condition=IfCondition(start_joint_controller),
)
initial_joint_controller_spawner_stopped = Node(
package="controller_manager",
executable="spawner",
arguments=[initial_joint_controller, "-c", "/controller_manager", "--inactive"],
condition=UnlessCondition(start_joint_controller),
)
gripper_controller = Node(
package="controller_manager",
executable="spawner",
arguments=["gripper_controller", "-c", "/controller_manager"],
condition=IfCondition(with_gripper_condition)
)
cartesian_motion_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["cartesian_motion_controller", "--inactive", "-c", "/controller_manager"],
condition=IfCondition(cartesian_controllers)
)
motion_control_handle_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["motion_control_handle", "--inactive", "-c", "/controller_manager"],
condition=IfCondition(cartesian_controllers)
)
cartesian_compliance_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["cartesian_compliance_controller", "--inactive", "-c", "/controller_manager"],
condition=IfCondition(cartesian_controllers)
)
# force_torque_sensor_broadcaster = Node(
# package="controller_manager",
# executable="spawner",
# arguments=["force_torque_sensor_broadcaster", "-c", "/controller_manager"]
# )
nodes_to_start = [
control_node,
joint_state_broadcaster_spawner,
initial_joint_controller_spawner_started,
initial_joint_controller_spawner_stopped,
gripper_controller,
cartesian_motion_controller_spawner,
motion_control_handle_spawner,
cartesian_compliance_controller_spawner,
# force_torque_sensor_broadcaster
]
return LaunchDescription(declared_arguments + nodes_to_start)

View file

@ -0,0 +1,153 @@
from launch_ros.actions import Node
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from rbs_launch_utils.launch_common import load_yaml
def generate_launch_description():
declared_arguments = []
declared_arguments.append(
DeclareLaunchArgument(
"robot_description",
default_value="''",
description="robot description string",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"robot_description_semantic",
default_value="''",
description="robot description semantic string",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"moveit_config_package",
default_value="rbs_arm",
description="MoveIt config package with robot SRDF/XACRO files. Usually the argument \
is not set, it enables use of a custom moveit config.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"moveit_config_file",
default_value="rbs_arm.srdf.xacro",
description="MoveIt SRDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"use_sim_time",
default_value="true",
description="Make MoveIt to use simulation time. This is needed for the trajectory planing in simulation.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"prefix",
default_value="''",
description="prefix for robot links",
)
)
prefix = LaunchConfiguration("prefix")
moveit_config_package = LaunchConfiguration("moveit_config_package")
moveit_config_file = LaunchConfiguration("moveit_config_file")
use_sim_time = LaunchConfiguration("use_sim_time")
robot_description_content = LaunchConfiguration("robot_description")
robot_description_semantic_content = LaunchConfiguration("robot_description_semantic")
robot_description = {"robot_description": robot_description_content}
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content}
use_sim_time = {"use_sim_time": use_sim_time}
robot_description_kinematics = PathJoinSubstitution(
[FindPackageShare(moveit_config_package), "config/moveit", "kinematics.yaml"]
)
# Planning Configuration
ompl_planning_pipeline_config = {
"move_group": {
"planning_plugin": "ompl_interface/OMPLPlanner",
"request_adapters": """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""",
"start_state_max_bounds_error": 0.1,
}
}
ompl_planning_yaml = load_yaml("rbs_arm", "config/moveit/ompl_planning.yaml")
ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml)
moveit_controllers = load_yaml("rbs_arm", "config/moveit/moveit_controllers.yaml")
trajectory_execution = {
"moveit_manage_controllers": True,
"trajectory_execution.allowed_execution_duration_scaling": 100.0,
"trajectory_execution.allowed_goal_duration_margin": 0.5,
"trajectory_execution.allowed_start_tolerance": 0.01,
}
planning_scene_monitor_parameters = {
"publish_planning_scene": True,
"publish_geometry_updates": True,
"publish_state_updates": True,
"publish_transforms_updates": True,
}
move_group_node = Node(
package="moveit_ros_move_group",
executable="move_group",
output="screen",
parameters=[
robot_description,
robot_description_semantic,
robot_description_kinematics,
ompl_planning_pipeline_config,
trajectory_execution,
moveit_controllers,
planning_scene_monitor_parameters,
use_sim_time,
],
)
move_topose_action_server = Node(
package="rbs_skill_servers",
executable="move_topose_action_server",
parameters=[
robot_description,
robot_description_semantic,
robot_description_kinematics,
use_sim_time,
]
)
move_cartesian_path_action_server = Node(
package="rbs_skill_servers",
executable="move_cartesian_path_action_server",
parameters=[
robot_description,
robot_description_semantic,
robot_description_kinematics,
use_sim_time,
]
)
move_joint_state_action_server = Node(
package="rbs_skill_servers",
executable="move_to_joint_states_action_server",
parameters=[
robot_description,
robot_description_semantic,
robot_description_kinematics,
use_sim_time,
]
)
nodes_to_start = [
move_group_node,
move_topose_action_server,
move_cartesian_path_action_server,
move_joint_state_action_server,
]
return LaunchDescription(declared_arguments + nodes_to_start)

View file

@ -0,0 +1,168 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, ExecuteProcess
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python.packages import get_package_share_directory
import os
def generate_launch_description():
declared_arguments = []
# General arguments
declared_arguments.append(
DeclareLaunchArgument(
"description_package",
default_value="rbs_arm",
description="Description package with robot URDF/XACRO files. Usually the argument \
is not set, it enables use of a custom description.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value="rbs_arm_modular.xacro",
description="URDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"prefix",
default_value='',
description="Prefix of the joint names, useful for \
multi-robot setup. If changed than also joint names in the controllers' configuration \
have to be updated.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"hardware",
default_value='',
# choices=["mock", "gazebo"],
description="The name of hardware",
)
)
prefix = LaunchConfiguration("prefix")
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
hardware = LaunchConfiguration("hardware")
rviz_config_file = PathJoinSubstitution(
[FindPackageShare(description_package), "config", "view_robot.rviz"]
)
initial_joint_controllers = PathJoinSubstitution(
[FindPackageShare("rbs_arm"), "config", "rbs_arm_controllers_gazebosim.yaml"]
)
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution([FindPackageShare(description_package), "urdf", description_file]),
" ",
"gripper_name:=", "", " ",
"prefix:=", prefix, " ",
"hardware:=", hardware, " ",
"simulation_controllers:=", initial_joint_controllers, " ",
]
)
robot_description = {"robot_description": robot_description_content}
# MoveIt Configuration
robot_description_semantic_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare("rbs_arm"), "config/moveit", "rbs_arm.srdf.xacro"]
),
" ",
"name:=","rbs_arm"," ",
"prefix:=",prefix," ",
]
)
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content}
robot_description_kinematics = PathJoinSubstitution(
[FindPackageShare("rbs_arm"), "moveit/config", "kinematics.yaml"]
)
moveit = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare(description_package),
'launch',
'moveit.launch.py'
])
]),
launch_arguments={
'robot_description': robot_description_content,
'robot_description_semantic': robot_description_semantic_content,
'prefix': prefix,
}.items())
load_joint_state_broadcaster = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
'joint_state_broadcaster'],
output='screen'
)
load_joint_trajectory_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
'joint_trajectory_controller'],
output='screen'
)
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
parameters=[
robot_description,
robot_description_semantic,
robot_description_kinematics
],
)
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory('ros_gz_sim'),
'launch', 'gz_sim.launch.py')]),
launch_arguments=[('gz_args', [' -r ', "empty.sdf"])],
)
# Spawn robot
gazebo_spawn_robot = Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-name', "rbs_arm",
'-x', '0.0',
'-z', '0.0',
'-y', '0.0',
'-string', robot_description_content
],
output='screen'
)
nodes_to_start = [
load_joint_state_broadcaster,
load_joint_trajectory_controller,
robot_state_publisher_node,
rviz_node,
gazebo,
gazebo_spawn_robot,
moveit
]
return LaunchDescription(declared_arguments + nodes_to_start)

454
rbs_arm/urdf/rbs_arm.urdf Normal file
View file

@ -0,0 +1,454 @@
<?xml version="1.0" encoding="UTF-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/urdf/rbs_arm_modular.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="rbs_arm">
<link name="world"/>
<joint name="base_link_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base_link"/>
</joint>
<link name="base_link">
<collision name="base_link_collision">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/start_link.stl" scale="1.00000 1.00000 1.00000"/>
</geometry>
</collision>
<inertial>
<inertia ixx="0.00503302470272442" ixy="0.000343817346410954" ixz="-4.74990755448368E-06" iyy="0.00337962410057753" iyz="-2.3099255620051E-05" izz="0.00405858207282473"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.000297002857922682 0.0964721185617698 -0.000361033370053684"/>
<mass value="1.88031044620482"/>
</inertial>
<visual name="base_link_visual">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/start_link.dae" scale="1.00000 1.00000 1.00000"/>
</geometry>
</visual>
</link>
<gazebo reference="base_link">
<visual>
<material>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.6 0.6 0.6 1</specular>
<ambient>1.0 1.0 1.0</ambient>
<lighting>true</lighting>
<emissive>0 0 0 1</emissive>
<pbr>
<metal>
<albedo_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/base_link_d.png</albedo_map>
<normal_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/base_link_n.png</normal_map>
<ambient_occlusion_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/base_link_ao.png</ambient_occlusion_map>
<roughness_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/base_link_r.png</roughness_map>
</metal>
</pbr>
</material>
</visual>
</gazebo>
<joint name="fork0_link_joint" type="revolute">
<limit effort="78" lower="-3.14159" upper="3.14159" velocity="0.52"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.17833"/>
<parent link="base_link"/>
<child link="fork0_link"/>
<axis xyz="0 0 1"/>
</joint>
<link name="fork0_link">
<collision name="fork0_link_collision">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/fork.stl" scale="1.00000 1.00000 1.00000"/>
</geometry>
</collision>
<inertial>
<inertia ixx="0.00367804533572758" ixy="1.04277925521833E-05" ixz="-0.00149971410403071" iyy="0.00415208849477534" iyz="-0.00122" izz="0.00329"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.0472051139085306 0.00208890925682996 0.0557265410642575"/>
<mass value="1.12472202892859"/>
</inertial>
<visual name="fork0_link_visual">
<origin rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/fork.dae" scale="1.00000 1.00000 1.00000"/>
</geometry>
</visual>
</link>
<ros2_control name="fork0_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="fork0_link_joint">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<param name="p">500</param>
<param name="d">0.5</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<gazebo reference="fork0_link">
<visual>
<material>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.6 0.6 0.6 1</specular>
<ambient>1.0 1.0 1.0</ambient>
<lighting>true</lighting>
<emissive>0 0 0 1</emissive>
<pbr>
<metal>
<albedo_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_d.png</albedo_map>
<normal_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_n.png</normal_map>
<ambient_occlusion_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_ao.png</ambient_occlusion_map>
<roughness_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_r.png</roughness_map>
</metal>
</pbr>
</material>
</visual>
</gazebo>
<joint name="main0_link_joint" type="revolute">
<limit effort="78" lower="-1.5708" upper="3.14159" velocity="0.52"/>
<origin rpy="-0.00000 0.00000 0.00000" xyz="0.10000 0.00000 0.09400"/>
<parent link="fork0_link"/>
<child link="main0_link"/>
<axis xyz="0 1 0"/>
</joint>
<link name="main0_link">
<collision name="main0_link_collision">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/main_link.stl" scale="1.00000 1.00000 1.00000"/>
</geometry>
</collision>
<inertial>
<inertia ixx="0.00315699373090845" ixy="2.84713820858537E-05" ixz="-7.01601261191721E-05" iyy="0.00343729241263707" iyz="-0.000101485203138902" izz="0.00125534890134052"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00186712264682627 -0.000412152188777604 0.0516389446895805"/>
<mass value="1.58688811563124"/>
</inertial>
<visual name="main0_link_visual">
<origin rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/main_link.dae" scale="1.00000 1.00000 1.00000"/>
</geometry>
</visual>
</link>
<ros2_control name="main0_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="main0_link_joint">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<param name="p">100</param>
<param name="d">0.5</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<gazebo reference="main0_link">
<visual>
<material>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.6 0.6 0.6 1</specular>
<ambient>1.0 1.0 1.0</ambient>
<lighting>true</lighting>
<emissive>0 0 0 1</emissive>
<pbr>
<metal>
<albedo_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_d.png</albedo_map>
<normal_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_n.png</normal_map>
<ambient_occlusion_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_ao.png</ambient_occlusion_map>
<roughness_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_r.png</roughness_map>
</metal>
</pbr>
</material>
</visual>
</gazebo>
<joint name="fork1_link_joint" type="revolute">
<limit effort="78" lower="-3.14159" upper="3.14159" velocity="0.52"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.13300"/>
<parent link="main0_link"/>
<child link="fork1_link"/>
<axis xyz="0 0 1"/>
</joint>
<link name="fork1_link">
<collision name="fork1_link_collision">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/fork.stl" scale="1.00000 1.00000 1.00000"/>
</geometry>
</collision>
<inertial>
<inertia ixx="0.00367804533572758" ixy="1.04277925521833E-05" ixz="-0.00149971410403071" iyy="0.00415208849477534" iyz="-0.00122" izz="0.00329"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.0472051139085306 0.00208890925682996 0.0557265410642575"/>
<mass value="1.12472202892859"/>
</inertial>
<visual name="fork1_link_visual">
<origin rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/fork.dae" scale="1.00000 1.00000 1.00000"/>
</geometry>
</visual>
</link>
<ros2_control name="fork1_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="fork1_link_joint">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<param name="p">500</param>
<param name="d">0.5</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<gazebo reference="fork1_link">
<visual>
<material>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.6 0.6 0.6 1</specular>
<ambient>1.0 1.0 1.0</ambient>
<lighting>true</lighting>
<emissive>0 0 0 1</emissive>
<pbr>
<metal>
<albedo_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_d.png</albedo_map>
<normal_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_n.png</normal_map>
<ambient_occlusion_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_ao.png</ambient_occlusion_map>
<roughness_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_r.png</roughness_map>
</metal>
</pbr>
</material>
</visual>
</gazebo>
<joint name="main1_link_joint" type="revolute">
<limit effort="78" lower="-1.5708" upper="3.14159" velocity="0.52"/>
<origin rpy="-0.00000 0.00000 0.00000" xyz="0.10000 0.00000 0.09400"/>
<parent link="fork1_link"/>
<child link="main1_link"/>
<axis xyz="0 1 0"/>
</joint>
<link name="main1_link">
<collision name="main1_link_collision">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/main_link.stl" scale="1.00000 1.00000 1.00000"/>
</geometry>
</collision>
<inertial>
<inertia ixx="0.00315699373090845" ixy="2.84713820858537E-05" ixz="-7.01601261191721E-05" iyy="0.00343729241263707" iyz="-0.000101485203138902" izz="0.00125534890134052"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00186712264682627 -0.000412152188777604 0.0516389446895805"/>
<mass value="1.58688811563124"/>
</inertial>
<visual name="main1_link_visual">
<origin rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/main_link.dae" scale="1.00000 1.00000 1.00000"/>
</geometry>
</visual>
</link>
<ros2_control name="main1_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="main1_link_joint">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<param name="p">100</param>
<param name="d">0.5</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<gazebo reference="main1_link">
<visual>
<material>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.6 0.6 0.6 1</specular>
<ambient>1.0 1.0 1.0</ambient>
<lighting>true</lighting>
<emissive>0 0 0 1</emissive>
<pbr>
<metal>
<albedo_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_d.png</albedo_map>
<normal_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_n.png</normal_map>
<ambient_occlusion_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_ao.png</ambient_occlusion_map>
<roughness_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/main_link_r.png</roughness_map>
</metal>
</pbr>
</material>
</visual>
</gazebo>
<joint name="fork2_link_joint" type="revolute">
<limit effort="78" lower="-3.14159" upper="3.14159" velocity="0.52"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.13300"/>
<parent link="main1_link"/>
<child link="fork2_link"/>
<axis xyz="0 0 1"/>
</joint>
<link name="fork2_link">
<collision name="fork2_link_collision">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/fork.stl" scale="1.00000 1.00000 1.00000"/>
</geometry>
</collision>
<inertial>
<inertia ixx="0.00367804533572758" ixy="1.04277925521833E-05" ixz="-0.00149971410403071" iyy="0.00415208849477534" iyz="-0.00122" izz="0.00329"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.0472051139085306 0.00208890925682996 0.0557265410642575"/>
<mass value="1.12472202892859"/>
</inertial>
<visual name="fork2_link_visual">
<origin rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/fork.dae" scale="1.00000 1.00000 1.00000"/>
</geometry>
</visual>
</link>
<ros2_control name="fork2_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="fork2_link_joint">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<param name="p">500</param>
<param name="d">0.5</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<gazebo reference="fork2_link">
<visual>
<material>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.6 0.6 0.6 1</specular>
<ambient>1.0 1.0 1.0</ambient>
<lighting>true</lighting>
<emissive>0 0 0 1</emissive>
<pbr>
<metal>
<albedo_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_d.png</albedo_map>
<normal_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_n.png</normal_map>
<ambient_occlusion_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_ao.png</ambient_occlusion_map>
<roughness_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/fork_r.png</roughness_map>
</metal>
</pbr>
</material>
</visual>
</gazebo>
<joint name="ee_link_joint" type="revolute">
<limit effort="78" lower="-1.5708" upper="3.14159" velocity="0.52"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.10000 0.00000 0.09473"/>
<parent link="fork2_link"/>
<child link="ee_link"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="tool0_joint" type="fixed">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.11000"/>
<parent link="ee_link"/>
<child link="tool0"/>
</joint>
<link name="tool0"/>
<link name="ee_link">
<collision name="ee_link_collision">
<origin rpy="-0.00000 0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/tail_link.stl" scale="1.00000 1.00000 1.00000"/>
</geometry>
</collision>
<inertial>
<inertia ixx="0.00147695259043549" ixy="-2.66894744420299E-05" ixz="-4.40871314563273E-05" iyy="0.00135500487881796" iyz="-3.19001462979333E-05" izz="0.00087582892706912"/>
<origin rpy="0.00000 0.00000 0.00000" xyz="-9.7531539777207E-06 -0.000888494418875867 0.0342332199538358"/>
<mass value="1.88031044620482"/>
</inertial>
<visual name="ee_link_visual">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000"/>
<geometry>
<mesh filename="file:///home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/tail_link.dae" scale="1.00000 1.00000 1.00000"/>
</geometry>
</visual>
</link>
<ros2_control name="ee_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="ee_link_joint">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<param name="p">10</param>
<param name="d">0.5</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<gazebo reference="ee_link">
<visual>
<material>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.6 0.6 0.6 1</specular>
<ambient>1.0 1.0 1.0</ambient>
<lighting>true</lighting>
<emissive>0 0 0 1</emissive>
<pbr>
<metal>
<albedo_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/ee_link_d.png</albedo_map>
<normal_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/ee_link_n.png</normal_map>
<ambient_occlusion_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/ee_link_ao.png</ambient_occlusion_map>
<roughness_map>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/materials/textures/ee_link_r.png</roughness_map>
</metal>
</pbr>
</material>
</visual>
</gazebo>
<gazebo>
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters>/home/bill-finger/rbs_ws/install/rbs_arm/share/rbs_arm/config/rbs_arm_controllers_gazebosim.yaml</parameters>
<controller_manager_node_name>/controller_manager</controller_manager_node_name>
</plugin>
</gazebo>
</robot>