urdf and srdf are not passed as dicts but as {'robot_description': <launch.substitutions.command.Command object at 0x7358a27fb6d0>} -> maybe the mistake

This commit is contained in:
Niko Feith 2024-03-21 13:03:03 +01:00
parent a8088a404c
commit 065a987c7b
3 changed files with 41 additions and 17 deletions

View File

@ -0,0 +1,9 @@
# Default initial positions for ur_robotiq's ros2_control fake system
initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
wrist_3_joint: 0

View File

@ -38,6 +38,7 @@ def generate_launch_description():
# File and package names
ur_description_package = "ur_description"
ur_moveit_config_package = "ur_moveit_config"
ur_robotiq_description_package = "ur_robotiq_description"
ur_robotiq_description_file = "ur_robotiq.urdf.xacro"
moveit_config_package = "ur_robotiq_moveit_config"
@ -125,9 +126,9 @@ def generate_launch_description():
robot_description_kinematics = load_yaml(moveit_config_package, "config/kinematics.yaml")
# robot_description_planning = {
# "robot_description_planning": load_yaml_abs(str(joint_limit_params.perform(context)))
# }
robot_description_planning = {
"robot_description_planning": load_yaml(ur_moveit_config_package, "config/joint_limits.yaml")
}
# Planning Configuration
ompl_planning_pipeline_config = {
@ -185,7 +186,7 @@ def generate_launch_description():
robot_description,
robot_description_semantic,
robot_description_kinematics,
# robot_description_planning,
robot_description_planning,
ompl_planning_pipeline_config,
trajectory_execution,
moveit_controllers,
@ -194,9 +195,10 @@ def generate_launch_description():
],
)
robot_state_publisher_node = launch_ros.actions.Node(
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)
@ -216,7 +218,7 @@ def generate_launch_description():
robot_description_semantic,
ompl_planning_pipeline_config,
robot_description_kinematics,
# robot_description_planning,
robot_description_planning,
],
)
@ -224,17 +226,17 @@ def generate_launch_description():
servo_yaml = load_yaml(moveit_config_package, "config/ur_servo.yaml")
servo_params = {"moveit_servo": servo_yaml}
# servo_node = Node(
# package="moveit_servo",
# condition=IfCondition(launch_servo),
# executable="servo_node_main",
# parameters=[
# servo_params,
# robot_description,
# robot_description_semantic,
# ],
# output="screen",
# )
servo_node = Node(
package="moveit_servo",
condition=IfCondition(launch_servo),
executable="servo_node_main",
parameters=[
servo_params,
robot_description,
robot_description_semantic,
],
output="screen",
)
# Declare the Launch arguments
# UR specific arguments

View File

@ -0,0 +1,13 @@
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur_robotiq_srdf">
<!-- robot name parameter -->
<xacro:arg name="name" default="ur"/>
<!-- parameters -->
<xacro:arg name="prefix" default="" />
<xacro:include filename="$(find ur_robotiq_moveit_config)/srdf/ur_robotiq_macro.srdf.xacro"/>
<xacro:ur_robotiq_srdf name="$(arg name)" prefix="$(arg prefix)"/>
</robot>