forked from felixduvallet/allegro-hand-ros
-
Notifications
You must be signed in to change notification settings - Fork 1
/
allegro_hand.launch
127 lines (105 loc) · 5.42 KB
/
allegro_hand.launch
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
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
<launch>
<!--
Required arguments:
HAND:=right|left
Suggested arguments:
NUM:=0|1|...
ZEROS:=/path/to/zeros_file.yaml
CONTROLLER:=grasp|pd|velsat|torque
RESPAWN:=true|false Respawn controller if it dies.
KEYBOARD:=true|false (default is true)
AUTO_CAN:=true|false (if true, ignores CAN_DEVICE argument and finds the can device automagically).
CAN_DEVICE:=/dev/pcanusb1 | /dev/pcanusbNNN (ls -l /dev/pcan* to see open CAN devices)
VISUALIZE:=true|false (Launch rviz)
This script launches the following nodes:
- allegro hand controller (different controllers exist)
- keyboard controller
- state publisher (for TF information)
NOTE: If you specify the can device manually (CAN_DEVICE:=/dev/pcanusbN),
make sure you *also* specify AUTO_CAN:=false.
-->
<!-- The inclusion of which_hand in the zero.yaml file has been deprecated.
Which hand (left/right) must now be specified as an argument when launching the Allegro Hand
as an input for both the robot_description and for the grasping library controllers. -->
<arg name="HAND" default="right" />
<arg name="NUM" default='0'/>
<!-- Visualization with rviz, only if arg VISUALIZE is set to true. Default is
false, the allegro_viz.launch can be started separated. -->
<arg name ="VISUALIZE" default="true" />
<include file="$(find allegro_hand_controllers)/launch/allegro_viz.launch"
if="$(arg VISUALIZE)">
<arg name="NUM" value="$(arg HAND)"/>
</include>
<arg name="CONTROLLER" default="pd"/> <!-- grasp, pd, velsat -->
<!-- Controllers include:
-grasp *
-pd
-velsat
-torque
*The default controller is 'grasp' which employs the included grasping library (libBHand). -->
<arg name="POLLING" default="true"/> <!-- true, false for polling the CAN communication -->
<!-- ls -l /dev/pcan* to see your open CAN ports. Auto means find it
automatically, and ignores the CAN_DEVICE argument. -->
<arg name="AUTO_CAN" default="true" />
<arg name="CAN_DEVICE" default="/dev/pcanusb1" />
<arg name="PARAMS_DIR" default="$(find allegro_hand_parameters)" />
<arg name="KEYBOARD" default="true" />
<!-- yaml param files for your hand can be found in parameters/zero_files/ -->
<arg name="ZEROS" default="$(arg PARAMS_DIR)/zero.yaml"/>
<!--If true, respawn the controller if it dies. -->
<arg name="RESPAWN" default="false"/>
<param name="/robot_description"
command="cat
$(find allegro_hand_description)/allegro_hand_description_$(arg HAND).urdf"/>
<param name="/allegro_hand_$(arg HAND)/robot_description"
command="cat
$(find allegro_hand_description)/allegro_hand_description_$(arg HAND).urdf"/>
<!-- Allegro Hand controller and communication node -->
<node name="allegro_hand_$(arg HAND)_$(arg HAND)"
pkg="allegro_hand_controllers"
type="allegro_node_$(arg CONTROLLER)"
output="screen"
clear_params="true"
respawn="$(arg RESPAWN)"
respawn_delay="2"
args="$(arg POLLING)" >
<!-- Remapping of topics into enumerated allegroHand_# namespace -->
<remap from="/allegroHand/joint_states" to="/allegro_hand_$(arg HAND)/joint_states"/>
<remap from="/allegroHand/joint_cmd" to="/allegro_hand_$(arg HAND)/joint_cmd"/>
<remap from="/allegroHand/lib_cmd" to="/allegro_hand_$(arg HAND)/lib_cmd"/>
<remap from="/allegroHand/torque_cmd" to="/allegro_hand_$(arg HAND)/torque_cmd"/>
<remap from="/allegroHand/envelop_torque" to="/allegro_hand_$(arg HAND)/envelop_torque"/>
<remap from="/allegroHand/joint_current_states" to="/allegro_hand_$(arg HAND)/joint_current_states"/>
<remap from="/allegroHand/joint_desired_states" to="/allegro_hand_$(arg HAND)/joint_desired_states"/>
<!--parameters are within the scope of the hand node so that multiple hands can be run at the same time -->
<rosparam file="$(arg ZEROS)" command="load" />
<rosparam file="$(arg PARAMS_DIR)/gains_pd.yaml" command="load" />
<rosparam file="$(arg PARAMS_DIR)/gains_velSat.yaml" command="load" />
<rosparam file="$(arg PARAMS_DIR)/initial_position.yaml" command="load" />
<!-- Set the CAN channel automatically (using detect_pcan.py) if the
AUTO_CAN parameter is true, otherwise use the CAN_DEVICE
argument. NOTE: To manually set the can device, you must *also* set
AUTO_CAN:=false. -->
<param name="/comm/CAN_CH" value="$(arg CAN_DEVICE)"
unless="$(arg AUTO_CAN)" />
<param name="/comm/CAN_CH"
command="$(find allegro_hand_description)/scripts/detect_pcan.py"
if="$(arg AUTO_CAN)" />
<param name="/hand_info/which_hand" value="$(arg HAND)" /> <!-- See HAND arg above -->
</node>
<!-- Joint States (angles) to Joint Transforms -->
<node name="jointState2tf_$(arg HAND)"
pkg="robot_state_publisher"
type="state_publisher">
<remap from="/tf" to="/allegro_hand_$(arg HAND)/tf"/>
<remap from="/joint_states" to="/allegro_hand_$(arg HAND)/joint_states"/>
</node>
<!-- Keyboard handler (if arg KEYBOARD is true) -->
<node name="keyboard_$(arg HAND)"
pkg="allegro_hand_keyboard"
type="allegro_hand_keyboard_node"
output="screen"
if="$(arg KEYBOARD)">
<remap from="/allegroHand/lib_cmd" to="/allegro_hand_$(arg HAND)/lib_cmd"/>
</node>
</launch>