Gripper has now a fake hardware controller (joint_trajectory_controller/JointTrajectoryController)
ur_robotiq_control.launch.py and ur_robotiq_moveit.launch.py work as expected
This commit is contained in:
parent
ce035fa6d7
commit
79aa262153
@ -27,6 +27,9 @@ controller_manager:
|
|||||||
robotiq_gripper_controller:
|
robotiq_gripper_controller:
|
||||||
type: position_controllers/GripperActionController
|
type: position_controllers/GripperActionController
|
||||||
|
|
||||||
|
robotiq_gripper_joint_trajectory_controller:
|
||||||
|
type: joint_trajectory_controller/JointTrajectoryController
|
||||||
|
|
||||||
robotiq_activation_controller:
|
robotiq_activation_controller:
|
||||||
type: robotiq_controllers/RobotiqActivationController
|
type: robotiq_controllers/RobotiqActivationController
|
||||||
|
|
||||||
@ -134,11 +137,27 @@ forward_position_controller:
|
|||||||
|
|
||||||
robotiq_gripper_controller:
|
robotiq_gripper_controller:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
default: true
|
|
||||||
joint: $(var tf_prefix)finger_joint
|
joint: $(var tf_prefix)finger_joint
|
||||||
use_effort_interface: true
|
use_effort_interface: true
|
||||||
use_speed_interface: true
|
use_speed_interface: true
|
||||||
|
|
||||||
|
robotiq_gripper_joint_trajectory_controller:
|
||||||
|
ros__parameters:
|
||||||
|
joints:
|
||||||
|
- $(var tf_prefix)finger_joint
|
||||||
|
command_interfaces:
|
||||||
|
- position
|
||||||
|
state_interfaces:
|
||||||
|
- position
|
||||||
|
- velocity
|
||||||
|
state_publish_rate: 100.0
|
||||||
|
action_monitor_rate: 20.0
|
||||||
|
allow_partial_joints_goal: false
|
||||||
|
constraints:
|
||||||
|
stopped_velocity_tolerance: 0.2
|
||||||
|
goal_time: 0.0
|
||||||
|
$(var tf_prefix)finger_joint: { trajectory: 0.2, goal: 0.1 }
|
||||||
|
|
||||||
robotiq_activation_controller:
|
robotiq_activation_controller:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
default: true
|
default: true
|
||||||
|
@ -215,6 +215,12 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
arguments=["robotiq_gripper_controller", "-c", "/controller_manager"],
|
arguments=["robotiq_gripper_controller", "-c", "/controller_manager"],
|
||||||
condition=UnlessCondition(use_fake_hardware),
|
condition=UnlessCondition(use_fake_hardware),
|
||||||
)
|
)
|
||||||
|
robotiq_gripper_joint_trajectory_controller_spawner = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["robotiq_gripper_joint_trajectory_controller", "-c", "/controller_manager"],
|
||||||
|
condition=IfCondition(use_fake_hardware),
|
||||||
|
)
|
||||||
|
|
||||||
robotiq_activation_controller_spawner = Node(
|
robotiq_activation_controller_spawner = Node(
|
||||||
package="controller_manager",
|
package="controller_manager",
|
||||||
@ -346,6 +352,7 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
control_node,
|
control_node,
|
||||||
ur_control_node,
|
ur_control_node,
|
||||||
robotiq_gripper_controller_spawner,
|
robotiq_gripper_controller_spawner,
|
||||||
|
robotiq_gripper_joint_trajectory_controller_spawner,
|
||||||
robotiq_activation_controller_spawner,
|
robotiq_activation_controller_spawner,
|
||||||
dashboard_client_node,
|
dashboard_client_node,
|
||||||
tool_communication_node,
|
tool_communication_node,
|
||||||
|
@ -3,6 +3,7 @@ controller_names:
|
|||||||
- scaled_joint_trajectory_controller
|
- scaled_joint_trajectory_controller
|
||||||
- joint_trajectory_controller
|
- joint_trajectory_controller
|
||||||
- robotiq_gripper_controller
|
- robotiq_gripper_controller
|
||||||
|
- robotiq_gripper_joint_trajectory_controller
|
||||||
|
|
||||||
|
|
||||||
scaled_joint_trajectory_controller:
|
scaled_joint_trajectory_controller:
|
||||||
@ -34,7 +35,13 @@ robotiq_gripper_controller:
|
|||||||
action_ns: gripper_cmd
|
action_ns: gripper_cmd
|
||||||
type: GripperCommand
|
type: GripperCommand
|
||||||
default: true
|
default: true
|
||||||
controlled_joints:
|
joints:
|
||||||
- finger_joint
|
- finger_joint
|
||||||
|
|
||||||
|
robotiq_gripper_joint_trajectory_controller:
|
||||||
|
action_ns: follow_joint_trajectory
|
||||||
|
type: FollowJointTrajectory
|
||||||
|
default: false
|
||||||
|
joints:
|
||||||
|
- finger_joint
|
||||||
|
|
||||||
|
@ -148,11 +148,14 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
# the scaled_joint_trajectory_controller does not work on fake hardware
|
# the scaled_joint_trajectory_controller does not work on fake hardware
|
||||||
use_fake_hw = use_fake_hardware.perform(context)
|
use_fake_hw = use_fake_hardware.perform(context)
|
||||||
controllers_yaml = load_yaml(moveit_config_package, "config/moveit_controllers.yaml")
|
controllers_yaml = load_yaml(moveit_config_package, "config/moveit_controllers.yaml")
|
||||||
|
print(controllers_yaml)
|
||||||
|
|
||||||
if use_fake_hw == "true":
|
if use_fake_hw == "true":
|
||||||
print("Using fake hardware")
|
print("Using fake hardware")
|
||||||
controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False
|
controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False
|
||||||
controllers_yaml["joint_trajectory_controller"]["default"] = True
|
controllers_yaml["joint_trajectory_controller"]["default"] = True
|
||||||
|
controllers_yaml["robotiq_gripper_controller"]["default"] = False
|
||||||
|
controllers_yaml["robotiq_gripper_joint_trajectory_controller"]["default"] = True
|
||||||
|
|
||||||
moveit_controllers = {
|
moveit_controllers = {
|
||||||
"moveit_simple_controller_manager": controllers_yaml,
|
"moveit_simple_controller_manager": controllers_yaml,
|
||||||
|
Loading…
Reference in New Issue
Block a user