issue with Gripper controllers

This commit is contained in:
Niko Feith 2024-03-21 17:12:24 +01:00
parent 8d1f4642dc
commit 124018526b
21 changed files with 347 additions and 146 deletions

View File

@ -134,7 +134,7 @@ forward_position_controller:
robotiq_gripper_controller:
ros__parameters:
default: true
joint: $(var tf_prefix)robotiq_140_left_knuckle_joint
joint: $(var tf_prefix)finger_joint
use_effort_interface: true
use_speed_interface: true

View File

@ -496,7 +496,7 @@ def generate_launch_description():
)
)
declared_arguments.append(
DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?")
DeclareLaunchArgument("launch_rviz", default_value="false", description="Launch RViz?")
)
declared_arguments.append(
DeclareLaunchArgument(

View File

@ -1,8 +1,8 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur_robotiq">
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur_manipulator">
<!-- parameters -->
<xacro:arg name="name" default="ur"/>
<xacro:arg name="name" default="ur_manipulator"/>
<!-- import main macro -->
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
<xacro:include filename="$(find ur_robotiq_description)/urdf/ur_to_robotiq_adapter.urdf.xacro" />
@ -52,7 +52,7 @@
<xacro:arg name="simulation_controllers" default="" />
<!-- initial position for simulations (Fake Hardware, Gazebo, Ignition) -->
<xacro:arg name="initial_positions_file" default="$(find ur_description)/config/initial_positions.yaml"/>
<xacro:arg name="initial_positions_file" default="$(find ur_robotiq_moveit_config)/config/initial_positions.yaml"/>
<!-- convert to property to use substitution in function -->
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="ur_robotiq_adapter">
<xacro:macro name="ur_to_robotiq" params="prefix parent child rotation:=^|${0.0}">
<joint name="${prefix}ur_to_robotiq_joint" type="fixed">

View File

@ -2,7 +2,6 @@ controller_names:
- scaled_joint_trajectory_controller
- joint_trajectory_controller
- robotiq_gripper_controller
- robotiq_activation_controller
scaled_joint_trajectory_controller:
@ -31,14 +30,11 @@ joint_trajectory_controller:
- wrist_3_joint
robotiq_gripper_controller:
action_ns: antipodal_gripper_action_controller
action_ns: position_controllers
type: GripperActionController
default: true
joint: robotiq_85_left_knuckle_joint
joints:
- finger_joint
use_effort_interface: true
use_speed_interface: true
robotiq_activation_controller:
action_ns: robotiq_controllers
type: RobotiqActivationController
default: true

View File

@ -1,6 +1,3 @@
# Default initial positions for ur_robotiq's ros2_control fake system
initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
shoulder_pan_joint: 0

View File

@ -4,7 +4,7 @@ ur_manipulator:
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
robotiq_gripper:
gripper:
ros__parameters:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005

View File

@ -52,7 +52,7 @@ planner_configs:
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
PRMstarkConfigDefault:
type: geometric::PRMstar
ur_arm:
ur_manipulator:
planner_configs:
- SBLkConfigDefault
- ESTkConfigDefault

View File

@ -1,3 +0,0 @@
controller_manager:
ros__parameters:
update_rate: 500 # Hz

View File

@ -1,7 +0,0 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_demo_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs()
return generate_demo_launch(moveit_config)

View File

@ -1,7 +0,0 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_move_group_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs()
return generate_move_group_launch(moveit_config)

View File

@ -1,7 +0,0 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_moveit_rviz_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs()
return generate_moveit_rviz_launch(moveit_config)

View File

@ -1,7 +0,0 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_rsp_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs()
return generate_rsp_launch(moveit_config)

View File

@ -1,7 +0,0 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_spawn_controllers_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs()
return generate_spawn_controllers_launch(moveit_config)

View File

@ -1,7 +0,0 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs()
return generate_static_virtual_joint_tfs_launch(moveit_config)

View File

@ -126,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(ur_moveit_config_package, "config/joint_limits.yaml")
}
# robot_description_planning = {
# "robot_description_planning": load_yaml(ur_moveit_config_package, "config/joint_limits.yaml")
# }
# Planning Configuration
ompl_planning_pipeline_config = {
@ -170,13 +170,6 @@ def generate_launch_description():
"publish_state_updates": True,
"publish_transforms_updates": True,
}
print(robot_description,
robot_description_semantic,
robot_description_kinematics,
ompl_planning_pipeline_config,
trajectory_execution,
moveit_controllers,
planning_scene_monitor_parameters)
# Start the actual move_group node/action server
move_group_node = Node(
package="moveit_ros_move_group",
@ -186,7 +179,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,
@ -195,13 +188,6 @@ def generate_launch_description():
],
)
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)
# rviz with moveit configuration
rviz_config_file = PathJoinSubstitution(
[FindPackageShare(moveit_config_package), "rviz", "view_robot.rviz"]
@ -218,7 +204,7 @@ def generate_launch_description():
robot_description_semantic,
ompl_planning_pipeline_config,
robot_description_kinematics,
robot_description_planning,
# robot_description_planning,
],
)
@ -277,6 +263,6 @@ def generate_launch_description():
launch_servo_arg
]
# servo_node,
nodes_to_start = [move_group_node, rviz_node, robot_state_publisher_node]
nodes_to_start = [move_group_node, rviz_node, servo_node]
return LaunchDescription(launch_args + nodes_to_start)

View File

@ -39,9 +39,17 @@
<exec_depend>rviz_common</exec_depend>
<exec_depend>rviz_default_plugins</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>ur_robotiq_description</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>ur_robotiq_description</exec_depend>
<exec_depend>ur_description</exec_depend>
<exec_depend>ur_robot_driver</exec_depend>
<exec_depend>ur_controllers</exec_depend>
<exec_depend>robotiq_description</exec_depend>
<exec_depend>robotiq_driver</exec_depend>
<exec_depend>robotiq_controllers</exec_depend>
<exec_depend>gripper_controllers</exec_depend>
<export>
<build_type>ament_cmake</build_type>

View File

@ -1,51 +0,0 @@
Panels:
- Class: rviz_common/Displays
Name: Displays
Property Tree Widget:
Expanded:
- /MotionPlanning1
- Class: rviz_common/Help
Name: Help
- Class: rviz_common/Views
Name: Views
Visualization Manager:
Displays:
- Class: rviz_default_plugins/Grid
Name: Grid
Value: true
- Class: moveit_rviz_plugin/MotionPlanning
Name: MotionPlanning
Planned Path:
Loop Animation: true
State Display Time: 0.05 s
Trajectory Topic: display_planned_path
Planning Scene Topic: monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 1
Scene Robot:
Robot Alpha: 0.5
Value: true
Global Options:
Fixed Frame: world
Tools:
- Class: rviz_default_plugins/Interact
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 2.0
Focal Point:
X: -0.1
Y: 0.25
Z: 0.30
Name: Current View
Pitch: 0.5
Target Frame: world
Yaw: -0.623
Window Geometry:
Height: 975
QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Width: 1200

View File

@ -0,0 +1,311 @@
Panels:
- Class: rviz_common/Displays
Help Height: 87
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
Splitter Ratio: 0.4957627058029175
Tree Height: 573
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Acceleration_Scaling_Factor: 0.1
Class: moveit_rviz_plugin/MotionPlanning
Enabled: true
Move Group Namespace: ""
MoveIt_Allow_Approximate_IK: false
MoveIt_Allow_External_Program: false
MoveIt_Allow_Replanning: false
MoveIt_Allow_Sensor_Positioning: false
MoveIt_Planning_Attempts: 10
MoveIt_Planning_Time: 5
MoveIt_Use_Cartesian_Path: false
MoveIt_Use_Constraint_Aware_IK: false
MoveIt_Warehouse_Host: 127.0.0.1
MoveIt_Warehouse_Port: 33829
MoveIt_Workspace:
Center:
X: 0
Y: 0
Z: 0
Size:
X: 2
Y: 2
Z: 2
Name: MotionPlanning
Planned Path:
Color Enabled: true
Interrupt Display: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
flange:
Alpha: 1
Show Axes: false
Show Trail: false
forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
shoulder_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
tool0:
Alpha: 1
Show Axes: false
Show Trail: false
upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_1_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_2_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_3_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Loop Animation: false
Robot Alpha: 0.5
Robot Color: 150; 50; 150
Show Robot Collision: false
Show Robot Visual: true
Show Trail: false
State Display Time: 0.05 s
Trail Step Size: 1
Trajectory Topic: /display_planned_path
Planning Metrics:
Payload: 1
Show Joint Torques: false
Show Manipulability: false
Show Manipulability Index: false
Show Weight Limit: false
TextHeight: 0.07999999821186066
Planning Request:
Colliding Link Color: 255; 0; 0
Goal State Alpha: 1
Goal State Color: 250; 128; 0
Interactive Marker Size: 0
Joint Violation Color: 255; 0; 255
Planning Group: ur_manipulator
Query Goal State: true
Query Start State: false
Show Workspace: false
Start State Alpha: 1
Start State Color: 0; 255; 0
Planning Scene Topic: monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 0.8999999761581421
Scene Color: 50; 230; 50
Scene Display Time: 0.009999999776482582
Show Scene Geometry: true
Voxel Coloring: Z-Axis
Voxel Rendering: Occupied Voxels
Scene Robot:
Attached Body Color: 150; 50; 150
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
flange:
Alpha: 1
Show Axes: false
Show Trail: false
forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
shoulder_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
tool0:
Alpha: 1
Show Axes: false
Show Trail: false
upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_1_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_2_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_3_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Robot Alpha: 1
Show Robot Collision: false
Show Robot Visual: true
Value: true
Velocity_Scaling_Factor: 0.1
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: world
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 6.619869709014893
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.2489434778690338
Y: -0.013962505385279655
Z: 0.13800443708896637
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.4103981554508209
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 1.210397720336914
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1381
Hide Left Dock: false
Hide Right Dock: false
MotionPlanning:
collapsed: false
MotionPlanning - Trajectory Slider:
collapsed: false
QMainWindow State: 000000ff00000000fd0000000400000000000001e0000004f6fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000007901000003fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000046000002e3000000ff01000003fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000005201000003fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000032a00000212000001b9010000030000000100000110000004f6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000046000004f6000000d701000003fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000070e000004f600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 2560
X: 0
Y: 30

View File

@ -2,7 +2,7 @@
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="ur_robotiq_srdf">
<!-- robot name parameter -->
<xacro:arg name="name" default="ur"/>
<xacro:arg name="name" default="ur_manipulator"/>
<!-- parameters -->
<xacro:arg name="prefix" default="" />

View File

@ -10,8 +10,7 @@
<chain base_link="${prefix}base_link" tip_link="${prefix}tool0" />
</group>
<group name="${prefix}gripper">
<link name="${prefix}robotiq_base_link"/>
<link name="${prefix}left_inner_knuckle"/>
<joint name="${prefix}finger_joint"/>
</group>
<!--GROUP STATES - Purpose - Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="${prefix}home" group="${prefix}${name}_manipulator">