diff --git a/sm_qr_search/launch/search_sim.launch b/sm_qr_search/launch/search_sim.launch new file mode 100644 index 0000000000000000000000000000000000000000..0623581730748f7fd123ea7a3dad8d2be290117d --- /dev/null +++ b/sm_qr_search/launch/search_sim.launch @@ -0,0 +1,69 @@ +<launch> + + <arg name="robot" default="darwin" /> + <arg name="environment" default="vision_env" /> + + + <include file="$(find darwin_description)/launch/darwin_sim.launch"> + <arg name="robot" value="$(arg robot)" /> + </include> + + <include file="$(find bioloid_description)/launch/vision_env.launch"> + <arg name="environment" value="$(arg environment)" /> + </include> + + <!-- launch the action client node --> + <node name="sm_qr_search" + pkg="sm_qr_search" + type="sm_qr_search" + output="screen" + ns="/darwin"> + <remap from="/darwin/sm_qr_search/cmd_vel" + to="/darwin/robot/cmd_vel"/> + <remap from="/darwin/sm_qr_search/set_walk_params" + to="/darwin/robot/set_walk_params"/> + <remap from="/darwin/sm_qr_search/set_servo_modules" + to="/darwin/robot/set_servo_modules"/> + <remap from="/darwin/head_follow_target" + to="/darwin/robot/head_follow_target"/> + <remap from="/darwin/sm_qr_search/head_target" + to="/darwin/robot/head_target"/> + <remap from="/darwin/sm_qr_search/joint_states" + to="/darwin/joint_states"/> + <remap from="/darwin/sm_qr_search/qr_pose" + to="/qr_detector/qr_pose"/> + <remap from="/darwin/joint_trajectory" + to="/darwin/robot/joint_trajectory"/> + </node> + + <!-- <include file="$(find darwin_apps)/launch/xs_camera_qr.launch"/>--> + <include file="$(find qr_detector)/launch/tracker_darwin.launch"/> + + <node pkg="image_view" + name="image_view" + type="image_view" + args="image:=/darwin/usb_cam/image_raw"> + </node> + + <!-- launch dynamic reconfigure --> + <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false" + output="screen"/> + + <!-- load the controllers --> + <node name="darwin_odometry" + pkg="darwin_odometry" + type="darwin_odometry" + output="screen" + ns="/darwin"> + <param name="left_leg_chain_file" value="$(find darwin_odometry)/config/left_leg.xml"/> + <param name="right_leg_chain_file" value="$(find darwin_odometry)/config/right_leg.xml"/> + <param name="tf_prefix" value="/darwin"/> + <param name="publish_tf" value="True"/> + <remap from="/darwin/darwin_odometry/joint_states" + to="/darwin/joint_states"/> + <remap from="/darwin/darwin_odometry/odom" + to="/darwin/sm_qr_search/odom"/> + </node> + +</launch> +