2018-05-27 22:08:36 +05:30

271 lines
8.7 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from line_follower.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="line_follower" xmlns:xacro="http://www.ros.org/wiki/xacro">
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/line_follower</robotNamespace>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
<alwaysOn>true</alwaysOn>
<legacyMode>false</legacyMode>
<updateRate>100</updateRate>
<leftJoint>left_wheel_hinge</leftJoint>
<rightJoint>right_wheel_hinge</rightJoint>
<wheelSeparation>0.25</wheelSeparation>
<wheelDiameter>0.2</wheelDiameter>
<wheelTorque>20</wheelTorque>
<commandTopic>line_follower/cmd_vel</commandTopic>
<publishWheelTF>true</publishWheelTF>
<wheelAcceleration>1</wheelAcceleration>
<odometryTopic>line_follower/odom_diffdrive</odometryTopic>
<publishWheelJointState>true</publishWheelJointState>
<odometryFrame>odom</odometryFrame>
<publishTf>true</publishTf>
<odometrySource>1</odometrySource>
<robotBaseFrame>footprint</robotBaseFrame>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_p3d.so" name="ground_truth">
<frameName>map</frameName>
<bodyName>chassis</bodyName>
<topicName>line_follower/odom</topicName>
<updateRate>30.0</updateRate>
</plugin>
</gazebo>
<gazebo reference="chassis">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="caster_wheel">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="camera">
<material>Gazebo/Grey</material>
<sensor name="camera1" type="camera">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_camera.so" name="camera_controller">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>line_follower/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<link name="footprint"/>
<joint name="base_joint" type="fixed">
<parent link="footprint"/>
<child link="chassis"/>
</joint>
<link name="chassis">
<collision>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<geometry>
<box size="0.4 0.2 0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<geometry>
<box size="0.4 0.2 0.1"/>
</geometry>
<material name="orange"/>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<mass value="1"/>
<inertia ixx="0.00416666666667" ixy="0" ixz="0" iyy="0.0141666666667" iyz="0" izz="0.0141666666667"/>
</inertial>
</link>
<joint name="fixed" type="fixed">
<parent link="chassis"/>
<child link="caster_wheel"/>
</joint>
<link name="caster_wheel">
<collision>
<origin rpy="0 0 0" xyz="-0.15 0 0.05"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="-0.15 0 0.05"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="-0.15 0 0.05"/>
<mass value="0.5"/>
<inertia ixx="0.0005" ixy="0" ixz="0" iyy="0.0005" iyz="0" izz="0.0005"/>
</inertial>
</link>
<link name="left_wheel">
<collision>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
<inertial>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.000541666666667" ixy="0" ixz="0" iyy="0.000541666666667" iyz="0" izz="0.001"/>
</inertial>
</link>
<gazebo reference="left_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<joint name="left_wheel_hinge" type="continuous">
<parent link="chassis"/>
<child link="left_wheel"/>
<origin rpy="0 0 0" xyz="0.1 -0.125 0.1"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<transmission name="left_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_wheel_hinge">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="leftMotor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>10</mechanicalReduction>
</actuator>
</transmission>
<link name="right_wheel">
<collision>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<material name="black"/>
</visual>
<inertial>
<origin rpy="0 1.57079632679 1.57079632679" xyz="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.000541666666667" ixy="0" ixz="0" iyy="0.000541666666667" iyz="0" izz="0.001"/>
</inertial>
</link>
<gazebo reference="right_wheel">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<joint name="right_wheel_hinge" type="continuous">
<parent link="chassis"/>
<child link="right_wheel"/>
<origin rpy="0 0 0" xyz="0.1 0.125 0.1"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<transmission name="right_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_wheel_hinge">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rightMotor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>10</mechanicalReduction>
</actuator>
</transmission>
<joint name="camera_joint" type="fixed">
<origin rpy="0 0.60 0" xyz="0.2 0 0.175"/>
<parent link="chassis"/>
<child link="camera"/>
</joint>
<link name="camera">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="4.16666666667e-06" ixy="0" ixz="0" iyy="4.16666666667e-06" iyz="0" izz="4.16666666667e-06"/>
</inertial>
</link>
</robot>