234 lines
7.8 KiB
XML
234 lines
7.8 KiB
XML
<?xml version="1.0"?>
|
|
<!--
|
|
|
|
Author: Jonathan Sprinkle, Sam Taylor, Alex Warren
|
|
Copyright (c) 2015 Arizona Board of Regents
|
|
All rights reserved.
|
|
|
|
Permission is hereby granted, without written agreement and without
|
|
license or royalty fees, to use, copy, modify, and distribute this
|
|
software and its documentation for any purpose, provided that the
|
|
above copyright notice and the following two paragraphs appear in
|
|
all copies of this software.
|
|
|
|
IN NO EVENT SHALL THE ARIZONA BOARD OF REGENTS BE LIABLE TO ANY PARTY
|
|
FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
|
|
ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
|
|
IF THE ARIZONA BOARD OF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF
|
|
SUCH DAMAGE.
|
|
|
|
THE ARIZONA BOARD OF REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES,
|
|
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY
|
|
AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER
|
|
IS ON AN "AS IS" BASIS, AND THE ARIZONA BOARD OF REGENTS HAS NO OBLIGATION
|
|
TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
|
|
|
|
Summary:
|
|
This file includes the control interfaces for ROS-based control
|
|
through Gazebo. For more information and for the tutorials used to create
|
|
this file, see
|
|
http://gazebosim.org/tutorials/?tut=ros_control#Prerequisites
|
|
|
|
-->
|
|
<robot>
|
|
|
|
|
|
<gazebo reference="back_right_wheel_link">
|
|
<mu1>1000000</mu1>
|
|
<mu2>1000000</mu2>
|
|
|
|
<kp>10000000</kp><!--kp is surface elasticity-->
|
|
<kd>100</kd><!-- kd is damping-->
|
|
<minDepth>0.01</minDepth>
|
|
<maxVel>1000.0</maxVel>
|
|
</gazebo>
|
|
|
|
<gazebo reference="back_left_wheel_link">
|
|
<mu1>100000000</mu1>
|
|
<mu2>100000000</mu2>
|
|
<kp>10000000</kp>
|
|
<kd>100</kd>
|
|
<minDepth>0.01</minDepth>
|
|
<maxVel>1000.0</maxVel>
|
|
</gazebo>
|
|
|
|
<gazebo reference="front_right_wheel_link">
|
|
<mu1>100000000</mu1>
|
|
<mu2>100000000</mu2>
|
|
<kp>1000000</kp>
|
|
<kd>100</kd>
|
|
<minDepth>0.01</minDepth>
|
|
<maxVel>1000.0</maxVel>
|
|
</gazebo>
|
|
|
|
<gazebo reference="front_left_wheel_link">
|
|
<mu1>100000000</mu1>
|
|
<mu2>100000000</mu2>
|
|
<kp>1000000</kp>
|
|
<kd>100</kd>
|
|
<minDepth>0.01</minDepth>
|
|
<maxVel>1000.0</maxVel>
|
|
</gazebo>
|
|
|
|
<gazebo reference="front_right_steering_link">
|
|
<mu1>100000000</mu1>
|
|
<mu2>100000000</mu2>
|
|
<kp>1000000</kp>
|
|
<kd>0.1</kd>
|
|
<minDepth>0.01</minDepth>
|
|
<maxVel>1000.0</maxVel>
|
|
</gazebo>
|
|
|
|
<gazebo reference="front_left_steering_link">
|
|
<mu1>100000000</mu1>
|
|
<mu2>100000000</mu2>
|
|
<kp>1000000</kp>
|
|
<kd>0.1</kd>
|
|
<minDepth>0.01</minDepth>
|
|
<maxVel>1000.0</maxVel>
|
|
</gazebo>
|
|
|
|
|
|
<!--camera-->
|
|
<!-- JMS removed to see if it improves sim times -->
|
|
<!--
|
|
<gazebo reference="camera_link">
|
|
<mu1>0.6</mu1>
|
|
<mu2>0.5</mu2>
|
|
</gazebo>
|
|
|
|
<gazebo reference="camera_link">
|
|
<sensor type="camera" name="camera1">
|
|
<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>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.007</stddev>
|
|
</noise>
|
|
</camera>
|
|
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
|
<alwaysOn>true</alwaysOn>
|
|
<updateRate>0.0</updateRate>
|
|
<robotNamespace>/$(arg roboname)</robotNamespace>
|
|
<cameraName>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>
|
|
-->
|
|
|
|
<gazebo reference="laser_link">
|
|
<mu1>0.6</mu1>
|
|
<mu2>0.5</mu2>
|
|
</gazebo>
|
|
|
|
<gazebo reference="laser_link">
|
|
<sensor type="ray" name="lidar_sensor">
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<visualize>false</visualize>
|
|
<update_rate>5</update_rate>
|
|
<ray>
|
|
<scan>
|
|
<horizontal>
|
|
<samples>100</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>-0.4</min_angle>
|
|
<max_angle>0.4</max_angle>
|
|
</horizontal>
|
|
<vertical>
|
|
<samples>20</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>-0.034906585</min_angle>
|
|
<!-- <max_angle>0.432841654</max_angle> -->
|
|
<max_angle>0.326</max_angle>
|
|
</vertical>
|
|
</scan>
|
|
<range>
|
|
<min>1</min>
|
|
<max>50.0</max>
|
|
<resolution>0.02</resolution>
|
|
</range>
|
|
</ray>
|
|
<!-- <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
|
|
<topicName>/cat/laser/scan</topicName>
|
|
<frameName>laser_link</frameName> -->
|
|
<plugin name="laser_controller" filename="libgazebo_ros_block_laser.so">
|
|
<frameName>laser_link</frameName>
|
|
<hokuyoMinIntensity>101</hokuyoMinIntensity>
|
|
<robotNamespace>/$(arg roboname)</robotNamespace>
|
|
<topicName>lidar_points</topicName>
|
|
<gaussianNoise>0.02</gaussianNoise>
|
|
<updateRate>5</updateRate>
|
|
</plugin>
|
|
</sensor>
|
|
</gazebo>
|
|
|
|
<gazebo>
|
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
|
<robotNamespace>/$(arg roboname)</robotNamespace>
|
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
|
<legacyModeNS>true</legacyModeNS>
|
|
</plugin>
|
|
</gazebo>
|
|
|
|
<!--Rear Wheel Drive, cuz why not-->
|
|
<!--
|
|
<gazebo>
|
|
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
|
|
<robotNamespace>/catvehicle</robotNamespace>
|
|
<rosDebugLevel>Debug</rosDebugLevel>
|
|
<publishWheelTF>false</publishWheelTF>
|
|
<publishWheelJointState>true</publishWheelJointState>
|
|
<alwaysOn>true</alwaysOn>
|
|
<leftJoint>back_left_wheel_joint</leftJoint>
|
|
<rightJoint>back_right_wheel_joint</rightJoint>
|
|
<wheelSeparation>1.73</wheelSeparation>
|
|
<wheelDiameter>0.712</wheelDiameter>
|
|
<wheelTorque>350</wheelTorque>
|
|
<wheelAcceleration>1.0</wheelAcceleration>
|
|
<commandTopic>cmd_vel</commandTopic>
|
|
<odometryTopic>odom</odometryTopic>
|
|
<odometryFrame>odom</odometryFrame>
|
|
<odometrySource>world</odometrySource>
|
|
<robotBaseFrame>base_link</robotBaseFrame>
|
|
<cmd_vel_timeout>0.20</cmd_vel_timeout>
|
|
<updateRate>10.0</updateRate>
|
|
</plugin>
|
|
</gazebo>
|
|
-->
|
|
|
|
<gazebo>
|
|
<plugin filename="libgazebo_ros_joint_state_publisher.so" name="joint_state_publisher">
|
|
<jointName>back_left_wheel_joint, back_right_wheel_joint, front_left_steering_joint, front_right_steering_joint, front_right_wheel_joint, front_left_wheel_joint</jointName>
|
|
<updateRate>50.0</updateRate>
|
|
<robotNamespace>/$(arg roboname)</robotNamespace>
|
|
<alwaysOn>true</alwaysOn>
|
|
</plugin>
|
|
</gazebo>
|
|
|
|
<gazebo>
|
|
<plugin name="cmdvel_controller" filename="libcatvehiclegazebo.so">
|
|
<robotNamespace>/$(arg roboname)</robotNamespace>
|
|
</plugin>
|
|
</gazebo>
|
|
</robot>
|