Skip to content

Commit 67a1d5f

Browse files
committed
Use velocity base forward command controller in simulation.
Signed-off-by: Jelmer de Wolde <jelmer.de.wolde@alliander.com>
1 parent 822150f commit 67a1d5f

3 files changed

Lines changed: 20 additions & 4 deletions

File tree

alliander_core/src/alliander_description/franka/config/controllers.yaml

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,22 @@
2020
gripper_action_controller:
2121
type: parallel_gripper_action_controller/GripperActionController
2222

23+
forward_command_controller:
24+
type: forward_command_controller/ForwardCommandController
25+
26+
forward_command_controller:
27+
ros__parameters:
28+
type: forward_command_controller/ForwardCommandController
29+
interface_name: velocity
30+
joints:
31+
- fr3_joint1
32+
- fr3_joint2
33+
- fr3_joint3
34+
- fr3_joint4
35+
- fr3_joint5
36+
- fr3_joint6
37+
- fr3_joint7
38+
2339
fr3_arm_controller:
2440
ros__parameters:
2541
allow_nonzero_velocity_at_trajectory_end: true

alliander_franka/src/alliander_franka/launch/controllers.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ def launch_setup(context: LaunchContext) -> list:
4242
package="controller_manager",
4343
executable="spawner",
4444
arguments=[
45-
"fr3_arm_controller",
45+
"forward_command_controller",
4646
"--switch-timeout",
4747
str(TIMEOUT),
4848
],

alliander_moveit/src/alliander_franka_moveit_config/config/servo_params.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,9 @@ pose_tracking:
3434
############################## OUTGOING COMMAND SETTINGS #######################
3535

3636
status_topic: "~/status"
37-
command_out_topic: "/fr3_arm_controller/joint_trajectory"
38-
command_out_type: "trajectory_msgs/JointTrajectory"
39-
publish_joint_positions: true
37+
command_out_topic: "/forward_command_controller/commands"
38+
command_out_type: "std_msgs/Float64MultiArray"
39+
publish_joint_positions: false
4040
publish_joint_velocities: true
4141
publish_joint_accelerations: false
4242

0 commit comments

Comments
 (0)