-
Notifications
You must be signed in to change notification settings - Fork 16
Expand file tree
/
Copy pathaico2_10_v1_controllers.yaml
More file actions
86 lines (73 loc) · 2.27 KB
/
aico2_10_v1_controllers.yaml
File metadata and controls
86 lines (73 loc) · 2.27 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
controller_manager:
ros__parameters:
update_rate: 1000 # Hz
left_rizon_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
right_rizon_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
gpio_controller_left:
type: gpio_controller/GPIOController
gpio_controller_right:
type: gpio_controller/GPIOController
flexiv_robot_states_broadcaster_left:
type: flexiv_robot_states_broadcaster/FlexivRobotStatesBroadcaster
flexiv_robot_states_broadcaster_right:
type: flexiv_robot_states_broadcaster/FlexivRobotStatesBroadcaster
left_rizon_arm_controller:
ros__parameters:
joints:
- $(var external_axis_prefix)aico2_10_v1_joint1
- $(var external_axis_prefix)aico2_10_v1_joint2
- $(var prefix_left)joint1
- $(var prefix_left)joint2
- $(var prefix_left)joint3
- $(var prefix_left)joint4
- $(var prefix_left)joint5
- $(var prefix_left)joint6
- $(var prefix_left)joint7
command_interfaces:
- position
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: true
constraints:
stopped_velocity_tolerance: 0.01
goal_time: 0.0
right_rizon_arm_controller:
ros__parameters:
joints:
- $(var prefix_right)joint1
- $(var prefix_right)joint2
- $(var prefix_right)joint3
- $(var prefix_right)joint4
- $(var prefix_right)joint5
- $(var prefix_right)joint6
- $(var prefix_right)joint7
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.01
goal_time: 0.0
flexiv_robot_states_broadcaster_left:
ros__parameters:
robot_sn: left_$(var robot_sn_left)
flexiv_robot_states_broadcaster_right:
ros__parameters:
robot_sn: right_$(var robot_sn_right)
gpio_controller_left:
ros__parameters:
robot_sn: left_$(var robot_sn_left)
gpio_controller_right:
ros__parameters:
robot_sn: right_$(var robot_sn_right)