73 lines
2.2 KiB
XML
73 lines
2.2 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
<gazebo reference="base_link">
|
|
<material>Gazebo/Blue</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="right_wheel_link">
|
|
<material>Gazebo/Gray</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="left_wheel_link">
|
|
<material>Gazebo/Gray</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="caster_wheel_link">
|
|
<material>Gazebo/Gray</material>
|
|
<mu1 value="0.1" />
|
|
<mu2 value="0.1" />
|
|
</gazebo>
|
|
|
|
|
|
<gazebo>
|
|
<plugin name="diff_drive_controller" filename="libgazebo_ros_diff_drive.so">
|
|
<!-- Update rate in Hz -->
|
|
<update_rate>50</update_rate>
|
|
<!-- Wheels -->
|
|
<left_joint>base_left_wheel_joint</left_joint>
|
|
<right_joint>base_right_wheel_joint</right_joint>
|
|
<!-- Size -->
|
|
<wheel_separation>${wheel_length + base_width}</wheel_separation>
|
|
<wheel_diameter>${wheel_radius}</wheel_diameter>
|
|
|
|
<!-- Ros Topic -->
|
|
<command_topic>cmd_vel</command_topic>
|
|
<!-- output -->
|
|
<publish_odom>true</publish_odom>
|
|
<publish_odom_tf>true</publish_odom_tf>
|
|
<publish_wheel_tf>true</publish_wheel_tf>
|
|
<odometry_topic>odom</odometry_topic>
|
|
<odometry_frame>odom</odometry_frame>
|
|
<robot_base_frame>base_footprint</robot_base_frame>
|
|
</plugin>
|
|
</gazebo>
|
|
|
|
|
|
<!-- Arm -->
|
|
<gazebo reference="arm_base_link">
|
|
<material>Gazebo/Orange</material>
|
|
</gazebo>
|
|
<gazebo reference="forearm_link">
|
|
<material>Gazebo/Yellow</material>
|
|
</gazebo>
|
|
<gazebo reference="hand_link">
|
|
<material>Gazebo/Orange</material>
|
|
</gazebo>
|
|
|
|
<gazebo>
|
|
<plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
|
|
<!-- Update rate in Hertz -->
|
|
<update_rate>10</update_rate>
|
|
|
|
<!-- Name of joints in the model whose states will be published. -->
|
|
<joint_name>arm_base_forearm_joint</joint_name>
|
|
<joint_name>forearm_hand_joint</joint_name>
|
|
</plugin>
|
|
</gazebo>
|
|
<gazebo>
|
|
<plugin name="joint_pose_trajectory" filename="libgazebo_ros_joint_pose_trajectory.so">
|
|
<update_rate>2</update_rate>
|
|
</plugin>
|
|
</gazebo>
|
|
|
|
</robot> |