diff --git a/darwin_apps/launch/stairs_client_sim.launch b/darwin_apps/launch/stairs_client_sim.launch new file mode 100644 index 0000000000000000000000000000000000000000..36811a21feceb842e238c9a54c4362f5989e4102 --- /dev/null +++ b/darwin_apps/launch/stairs_client_sim.launch @@ -0,0 +1,61 @@ +<launch> + + <arg name="robot" default="darwin" /> + <arg name="environment" default="stairs_env" /> + + <include file="$(find darwin_description)/launch/darwin_sim.launch"> + <arg name="robot" value="$(arg robot)" /> + </include> + + <include file="$(find bioloid_description)/launch/stairs_env.launch"> + <arg name="environment" value="$(arg environment)" /> + </include> + + <!-- launch the stairs client node --> + <node name="stairs_client" + pkg="stairs_client" + type="stairs_client" + output="screen" + ns="/darwin"> + <param name="SHIFT_WEIGHT_RIGHT_TIME" value="1.6"/> + <param name="RISE_RIGHT_FOOT_TIME" value="3.2"/> + <param name="ADVANCE_RIGHT_FOOT_TIME" value="4.8"/> + <param name="CONTACT_RIGHT_FOOT_TIME" value="6.4"/> + <param name="SHIFT_WEIGHT_RIGHT_TIME" value="8.0"/> + <param name="RISE_LEFT_FOOT_TIME" value="9.6"/> + <param name="ADVANCE_LEFT_FOOT_TIME" value="11.2"/> + <param name="CONTACT_LEFT_FOOT_TIME" value="12.8"/> + <param name="CENTER_WEIGHT_TIME" value="14.4"/> + <param name="X_OFFSET" value="-0.01"/> + <param name="Y_OFFSET" value="0.005"/> + <param name="Z_OFFSET" value="0.02"/> + <param name="R_OFFSET" value="0.0"/> + <param name="P_OFFSET" value="0.0"/> + <param name="A_OFFSET" value="0.0"/> + <param name="Y_SHIFT" value="0.04"/> + <param name="X_SHIFT" value="0.08"/> + <param name="Z_OVERSHOOT" value="0.015"/> + <param name="Z_HEIGHT" value="0.03"/> + <param name="HIP_PITCH_OFFSET" value="0.23"/> + <param name="R_SHIFT" value="0.05"/> + <param name="P_SHIFT" value="0.1"/> + <param name="A_SHIFT" value="0.3"/> + <param name="Y_SPREAD" value="0.02"/> + <param name="X_SHIFT_BODY" value="0.035"/> + <remap from="/darwin/stairs_client/stairs_client/climb_stairs" + to="/darwin/robot/climb_stairs"/> + <remap from="/darwin/stairs_client/stairs_client/set_stairs_params" + to="/darwin/robot/set_stairs_params"/> + <remap from="/darwin/stairs_client/stairs_client/get_stairs_params" + to="/darwin/robot/get_stairs_params"/> + <remap from="/darwin/stairs_client/stairs_client/set_servo_modules" + to="/darwin/robot/set_servo_modules"/> + <remap from="/darwin/stairs_client/stairs_client/fallen_state" + to="/darwin/robot/fallen_state"/> + </node> + + <!-- launch dynamic reconfigure --> + <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false" + output="screen"/> + +</launch>