--- /dev/null
+<launch>
+
+ <!-- joy node -->
+ <node name="joy_node" pkg="joy" type="joy_node" respawn="true">
+ <param name="dev" type="string" value="/dev/input/js0" />
+ <param name="deadzone" value="0.12" />
+ </node>
+
+ <!-- WAM Teleop Node -->
+ <node pkg="wam_teleop" type="wam_joystick_teleop" name="wam_wingman" output="screen" />
+
+
+ <param name="deadman_button" type="int" value="0" /> <!-- fire -->
+ <param name="guardian_deadman_button" type="int" value="4" /> <!-- O5 -->
+
+ <param name="gripper_open_button" type="int" value="9" /> <!-- H2 up -->
+ <param name="gripper_close_button" type="int" value="11" /> <!-- H2 down -->
+ <param name="spread_open_button" type="int" value="10" /> <!-- H2 right -->
+ <param name="spread_close_button" type="int" value="12" /> <!-- H2 left -->
+
+ <param name="orientation_control_button" type="int" value="3" /> <!-- O4 -->
+ <param name="go_home_button" type="int" value="1" /> <!-- O2 -->
+ <param name="hold_joints_button" type="int" value="2" /> <!-- O3 -->
+
+ <param name="grasp_max_velocity" type="double" value="1.0" />
+ <param name="spread_max_velocity" type="double" value="1.0" />
+ <param name="cartesian_magnitude" type="double" value="0.05" />
+ <param name="orientation_magnitude" type="double" value="1.0" />
+
+ <param name="cartesian_x_axis" type="int" value="0" /> <!-- X axis -->
+ <param name="cartesian_y_axis" type="int" value="1" /> <!-- Y axis -->
+ <param name="cartesian_z_axis" type="int" value="2" /> <!-- Z axis -->
+
+ <param name="orientation_roll_axis" type="int" value="0" /> <!-- X axis -->
+ <param name="orientation_pitch_axis" type="int" value="1" /> <!-- Y axis -->
+ <param name="orientation_yaw_axis" type="int" value="2" /> <!-- Z axis -->
+</launch>
n_.param("orientation_magnitude", ortn_mag, 1.0);
n_.param("cartesian_x_axis", axis_x, 3);
n_.param("cartesian_y_axis", axis_y, 2);
- n_.param("cartesian_x_axis", axis_z, 1);
+ n_.param("cartesian_z_axis", axis_z, 1);
n_.param("orientation_roll_axis", axis_r, 3);
n_.param("orientation_pitch_axis", axis_p, 2);
n_.param("orientation_yaw_axis", axis_yaw, 1);