75 lines
2.3 KiB
XML
Executable File
75 lines
2.3 KiB
XML
Executable File
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
|
|
|
<!-- Arguments used in cititruck.gazebo -->
|
|
<xacro:arg name="controller_prefix" default=""/>
|
|
<xacro:arg name="sensor_prefix" default=""/>
|
|
<xacro:arg name="sick_name" default="safety"/>
|
|
<xacro:arg name="ls2000_name" default="nav"/>
|
|
<xacro:arg name="kinect2_name" default=""/>
|
|
<xacro:arg name="kinect1_name" default="kinect"/>
|
|
<xacro:arg name="use_gpu" default="true"/>
|
|
|
|
<!-- ros_control plugin -->
|
|
<gazebo>
|
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
|
<robotNamespace>/cititruck</robotNamespace>
|
|
</plugin>
|
|
</gazebo>
|
|
|
|
<gazebo>
|
|
<plugin name="steer_drive_controller" filename="libgazebo_ros_steer_drive.so">
|
|
<legacyMode>false</legacyMode>
|
|
<alwaysOn>true</alwaysOn>
|
|
<updateRate>100</updateRate>
|
|
<steerJoint>base2steer_joint</steerJoint>
|
|
<driveJoint>steer2sd_wheel_joint</driveJoint>
|
|
<fixedWheelLeftJoint>base2fixed_left_wheel_joint</fixedWheelLeftJoint>
|
|
<fixedWheelRightJoint>base2fixed_right_wheel_joint</fixedWheelRightJoint>
|
|
|
|
<wheelDiameter>0.16</wheelDiameter>
|
|
<steeringFixWheelDistanceX>1.190</steeringFixWheelDistanceX>
|
|
<steeringFixWheelDistanceY>0.0</steeringFixWheelDistanceY>
|
|
|
|
<steerTorque>1000</steerTorque>
|
|
<driveTorque>1000</driveTorque>
|
|
|
|
<commandTopic>$(arg controller_prefix)cmd_vel</commandTopic>
|
|
<odometryTopic>odom</odometryTopic>
|
|
<odometryFrame>/world</odometryFrame>
|
|
<robotBaseFrame>base_footprint</robotBaseFrame>
|
|
|
|
<odomEncSteeringAngleOffset>0.01</odomEncSteeringAngleOffset>
|
|
|
|
<!--odometrySource>encoder</odometrySource-->
|
|
|
|
<publishWheelJointState>true</publishWheelJointState>
|
|
</plugin>
|
|
</gazebo>
|
|
|
|
<gazebo reference="base_link" >
|
|
<material>Gazebo/Red</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="left_fork" >
|
|
<material>Gazebo/Grey</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="right_fork" >
|
|
<material>Gazebo/Grey</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="fixed_left_wheel_link" >
|
|
<material>Gazebo/Black</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="fixed_right_wheel_link" >
|
|
<material>Gazebo/Black</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="steerdrive_wheel_link" >
|
|
<material>Gazebo/Black</material>
|
|
</gazebo>
|
|
|
|
</robot>
|