From: <wa...@us...> - 2009-08-10 04:58:19
|
Revision: 21309 http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21309&view=rev Author: wattsk Date: 2009-08-10 04:58:11 +0000 (Mon, 10 Aug 2009) Log Message: ----------- Combining teleop launch file #2297 Modified Paths: -------------- pkg/trunk/stacks/pr2/pr2_alpha/teleop_joystick.launch pkg/trunk/stacks/pr2/pr2_alpha/teleop_keyboard.launch pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch Added Paths: ----------- pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch Added: pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch =================================================================== --- pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch (rev 0) +++ pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch 2009-08-10 04:58:11 UTC (rev 21309) @@ -0,0 +1,17 @@ +<launch> + <!-- Watts: Contains all controllers necessary to teleop_pr2, avoids code + reuse in teleop_joystick, teleop_ps3 --> + + <rosparam file="$(find pr2_default_controllers)/pr2_base_controller.yaml" command="load" ns="pr2_base_controller" /> + <rosparam file="$(find pr2_default_controllers)/pr2_odometry.yaml" command="load" ns="pr2_odometry" /> + <node pkg="mechanism_control" type="spawner.py" args="pr2_base_controller pr2_odometry" output="screen"/> + + <rosparam file="$(find pr2_default_controllers)/pr2_joint_velocity_controllers.yaml" command="load" /> + <node pkg="mechanism_control" type="spawner.py" args="torso_lift_velocity_controller" output="screen" /> + + <include file="$(find pr2_default_controllers)/head_position_controller.launch" /> + + + <!-- The robot pose EKF is launched with the base controller--> + <include file="$(find robot_pose_ekf)/robot_pose_ekf.launch" /> +</launch> Modified: pkg/trunk/stacks/pr2/pr2_alpha/teleop_joystick.launch =================================================================== --- pkg/trunk/stacks/pr2/pr2_alpha/teleop_joystick.launch 2009-08-10 04:43:37 UTC (rev 21308) +++ pkg/trunk/stacks/pr2/pr2_alpha/teleop_joystick.launch 2009-08-10 04:58:11 UTC (rev 21309) @@ -1,48 +1,37 @@ <launch> - <rosparam file="$(find pr2_default_controllers)/pr2_base_controller.yaml" command="load" ns="pr2_base_controller" /> - <rosparam file="$(find pr2_default_controllers)/pr2_odometry.yaml" command="load" ns="pr2_odometry" /> - <node pkg="mechanism_control" type="spawner.py" args="pr2_base_controller pr2_odometry" output="screen"/> - - <rosparam file="$(find pr2_default_controllers)/pr2_joint_velocity_controllers.yaml" command="load" /> - <node pkg="mechanism_control" type="spawner.py" args="torso_lift_velocity_controller" output="screen" /> - - <include file="$(find pr2_default_controllers)/head_position_controller.launch" /> - - - <!-- The robot pose EKF is launched with the base controller--> - <include file="$(find robot_pose_ekf)/robot_pose_ekf.launch" /> - - <group name="joystick_teleop"> - <!-- Axes --> - <param name="axis_vx" value="3" type="int"/> - <param name="axis_vy" value="2" type="int"/> - <param name="axis_vw" value="0" type="int"/> - <param name="axis_pan" value="0" type="int"/> - <param name="axis_tilt" value="3" type="int"/> - - <!-- Base velocities --> - <param name="max_vw" value="0.8" /> - <param name="max_vx" value="0.5" /> - <param name="max_vy" value="0.5" /> - <param name="max_vw_run" value="1.4" /> - <param name="max_vx_run" value="1.0" /> - <param name="max_vy_run" value="1.0" /> - - <!-- Head --> - <param name="max_pan" value="2.7" /> - <param name="max_tilt" value="1.4" /> - <param name="min_tilt" value="-0.4" /> - <param name="tilt_step" value="0.015" /> - <param name="pan_step" value="0.02" /> - - <!-- Button maps for logitech --> - <param name="run_button" value="5" type="int" /> - <param name="torso_dn_button" value="1" type="int" /> - <param name="torso_up_button" value="3" type="int" /> - <param name="head_button" value="6" type="int" /> - <param name="deadman_button" value="4" type="int"/> - - <node pkg="teleop_pr2" type="teleop_pr2" output="screen"/> - </group> + <include file="$(find pr2_alpha)/teleop_controllers.launch" /> + + <group name="joystick_teleop"> + <!-- Axes --> + <param name="axis_vx" value="3" type="int"/> + <param name="axis_vy" value="2" type="int"/> + <param name="axis_vw" value="0" type="int"/> + <param name="axis_pan" value="0" type="int"/> + <param name="axis_tilt" value="3" type="int"/> + + <!-- Base velocities --> + <param name="max_vw" value="0.8" /> + <param name="max_vx" value="0.5" /> + <param name="max_vy" value="0.5" /> + <param name="max_vw_run" value="1.4" /> + <param name="max_vx_run" value="1.0" /> + <param name="max_vy_run" value="1.0" /> + + <!-- Head --> + <param name="max_pan" value="2.7" /> + <param name="max_tilt" value="1.4" /> + <param name="min_tilt" value="-0.4" /> + <param name="tilt_step" value="0.015" /> + <param name="pan_step" value="0.02" /> + + <!-- Button maps for logitech --> + <param name="run_button" value="5" type="int" /> + <param name="torso_dn_button" value="1" type="int" /> + <param name="torso_up_button" value="3" type="int" /> + <param name="head_button" value="6" type="int" /> + <param name="deadman_button" value="4" type="int"/> + + <node pkg="teleop_pr2" type="teleop_pr2" output="screen"/> + </group> </launch> Modified: pkg/trunk/stacks/pr2/pr2_alpha/teleop_keyboard.launch =================================================================== --- pkg/trunk/stacks/pr2/pr2_alpha/teleop_keyboard.launch 2009-08-10 04:43:37 UTC (rev 21308) +++ pkg/trunk/stacks/pr2/pr2_alpha/teleop_keyboard.launch 2009-08-10 04:58:11 UTC (rev 21309) @@ -1,26 +1,15 @@ <launch> + <!-- This controller file has the torso and head, which is unnecessary + but not harmful --> + <include file="$(find pr2_alpha)/teleop_controllers.launch" /> - <rosparam file="$(find pr2_default_controllers)/pr2_base_controller.yaml" command="load" ns="pr2_base_controller" /> - <rosparam file="$(find pr2_default_controllers)/pr2_odometry.yaml" command="load" ns="pr2_odometry" /> - <node pkg="mechanism_control" type="spawner.py" args="pr2_base_controller pr2_odometry" output="screen"/> - - <!-- The robot pose EKF is launched with the base controller--> - <group ns="robot_pose_ekf"> - <param name="freq" value="30.0"/> - <param name="sensor_timeout" value="1.0"/> - <param name="odom_used" value="true"/> - <param name="imu_used" value="true"/> - <param name="vo_used" value="false"/> + <group name="keyboard_teleop" > + <param name="walk_vel" value="0.5" /> + <param name="run_vel" value="1.0" /> + <param name="yaw_rate" value="1.0" /> + <param name="yaw_run_rate" value="1.5" /> + + <node pkg="teleop_pr2" type="teleop_pr2_keyboard" output="screen"/> </group> - <node pkg="robot_pose_ekf" type="robot_pose_ekf" args="robot_pose_ekf"/> - - <param name="walk_vel" value="0.5" /> - <param name="run_vel" value="1.0" /> - <param name="yaw_rate" value="1.0" /> - <param name="yaw_run_rate" value="1.5" /> - - - <node pkg="teleop_pr2" type="teleop_pr2_keyboard" output="screen"/> - </launch> Modified: pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch =================================================================== --- pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch 2009-08-10 04:43:37 UTC (rev 21308) +++ pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch 2009-08-10 04:58:11 UTC (rev 21309) @@ -1,48 +1,37 @@ <launch> - <rosparam file="$(find pr2_default_controllers)/pr2_base_controller.yaml" command="load" ns="pr2_base_controller" /> - <rosparam file="$(find pr2_default_controllers)/pr2_odometry.yaml" command="load" ns="pr2_odometry" /> - <node pkg="mechanism_control" type="spawner.py" args="pr2_base_controller pr2_odometry" output="screen"/> - - <rosparam file="$(find pr2_default_controllers)/pr2_joint_velocity_controllers.yaml" command="load" /> - <node pkg="mechanism_control" type="spawner.py" args="torso_lift_velocity_controller" output="screen" /> - - <include file="$(find pr2_default_controllers)/head_position_controller.launch" /> - - - <!-- The robot pose EKF is launched with the base controller--> - <include file="$(find robot_pose_ekf)/robot_pose_ekf.launch" /> - - <group name="ps3_teleop"> - <!-- Axes --> - <param name="axis_vx" value="3" type="int"/> - <param name="axis_vy" value="2" type="int"/> - <param name="axis_vw" value="0" type="int"/> - <param name="axis_pan" value="0" type="int"/> - <param name="axis_tilt" value="3" type="int"/> - - <!-- Base velocities --> - <param name="max_vw" value="0.8" /> - <param name="max_vx" value="0.5" /> - <param name="max_vy" value="0.5" /> - <param name="max_vw_run" value="1.4" /> - <param name="max_vx_run" value="1.0" /> - <param name="max_vy_run" value="1.0" /> - - <!-- Head --> - <param name="max_pan" value="2.7" /> - <param name="max_tilt" value="1.4" /> - <param name="min_tilt" value="-0.4" /> - <param name="tilt_step" value="0.015" /> - <param name="pan_step" value="0.02" /> - - <!-- Buttons have changed for PS3 controller mapping --> - <param name="run_button" value="7" type="int" /> - <param name="torso_dn_button" value="1" type="int" /> - <param name="torso_up_button" value="2" type="int" /> - <param name="head_button" value="4" type="int" /> - <param name="deadman_button" value="6" type="int"/> - - <node pkg="teleop_pr2" type="teleop_pr2" output="screen"/> - </group> + <include file="$(find pr2_alpha)/teleop_controllers.launch" /> + + <group name="ps3_teleop"> + <!-- Axes --> + <param name="axis_vx" value="3" type="int"/> + <param name="axis_vy" value="2" type="int"/> + <param name="axis_vw" value="0" type="int"/> + <param name="axis_pan" value="0" type="int"/> + <param name="axis_tilt" value="3" type="int"/> + + <!-- Base velocities --> + <param name="max_vw" value="0.8" /> + <param name="max_vx" value="0.5" /> + <param name="max_vy" value="0.5" /> + <param name="max_vw_run" value="1.4" /> + <param name="max_vx_run" value="1.0" /> + <param name="max_vy_run" value="1.0" /> + + <!-- Head --> + <param name="max_pan" value="2.7" /> + <param name="max_tilt" value="1.4" /> + <param name="min_tilt" value="-0.4" /> + <param name="tilt_step" value="0.015" /> + <param name="pan_step" value="0.02" /> + + <!-- Buttons have changed for PS3 controller mapping --> + <param name="run_button" value="7" type="int" /> + <param name="torso_dn_button" value="1" type="int" /> + <param name="torso_up_button" value="2" type="int" /> + <param name="head_button" value="4" type="int" /> + <param name="deadman_button" value="6" type="int"/> + + <node pkg="teleop_pr2" type="teleop_pr2" output="screen"/> + </group> </launch> This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |