tb_create_mobile_base.launch.xml 1.7 KB

123456789101112131415161718192021222324252627282930313233343536
  1. <launch>
  2. <!-- Turtlebot Driver -->
  3. <node pkg="create_node" type="turtlebot_node.py" name="turtlebot_node" respawn="true" args="--respawnable">
  4. <param name="bonus" value="false" />
  5. <param name="update_rate" value="30.0" />
  6. <param name="port" value="/dev/ttyUSB0" />
  7. <remap from="cmd_vel" to="mobile_base/commands/velocity" />
  8. <remap from="turtlebot_node/sensor_state" to="mobile_base/sensors/core" />
  9. <remap from="imu/data" to="mobile_base/sensors/imu_data" />
  10. <remap from="imu/raw" to="mobile_base/sensors/imu_data_raw" />
  11. </node>
  12. <!-- Enable breaker 1 for the kinect -->
  13. <node pkg="create_node" type="kinect_breaker_enabler.py" name="kinect_breaker_enabler"/>
  14. <!-- The odometry estimator -->
  15. <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
  16. <remap from="imu_data" to="mobile_base/sensors/imu_data"/>
  17. <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
  18. <param name="freq" value="10.0"/>
  19. <param name="sensor_timeout" value="1.0"/>
  20. <param name="publish_tf" value="true"/>
  21. <param name="odom_used" value="true"/>
  22. <param name="imu_used" value="true"/>
  23. <param name="vo_used" value="false"/>
  24. <param name="output_frame" value="odom"/>
  25. </node>
  26. <!-- velocity commands multiplexer -->
  27. <node pkg="nodelet" type="nodelet" name="mobile_base_nodelet_manager" args="manager"/>
  28. <node pkg="nodelet" type="nodelet" name="cmd_vel_mux" args="load yocs_cmd_vel_mux/CmdVelMuxNodelet mobile_base_nodelet_manager">
  29. <param name="yaml_cfg_file" value="$(find turtlebot_bringup)/param/mux.yaml"/>
  30. <remap from="cmd_vel_mux/output" to="mobile_base/commands/velocity"/>
  31. <remap from="cmd_vel_mux/input/navi" to="cmd_vel"/>
  32. </node>
  33. </launch>