--- /dev/null
+joint_state_controller:
+ type: "joint_state_controller/JointStateController"
+ publish_rate: 20
+
+diff_drive_controller:
+ type: "diff_drive_controller/DiffDriveController"
+ left_wheel: ['front_left_wheel_joint', 'rear_left_wheel_joint']
+ right_wheel: ['front_right_wheel_joint', 'rear_right_wheel_joint']
+ publish_rate: 20
+ pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
+ twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
+ cmd_vel_timeout: 1000000000
+
+ # Base frame_id
+ base_frame_id: base_footprint
+
+ # Odometry fused with IMU is published by robot_localization, so
+ # no need to publish a TF based on encoders alone.
+ enable_odom_tf: false
+
+ # Hardware provides wheel velocities
+ estimate_velocity_from_position: false
+
+ # Wheel separation and radius multipliers
+ wheel_separation_multiplier: 1.0 # default: 1.0
+ wheel_radius_multiplier : 1.0 # default: 1.0
+
+ # Velocity and acceleration limits
+ # Whenever a min_* is unspecified, default to -max_*
+ linear:
+ x:
+ has_velocity_limits : true
+ max_velocity : 1.5 # m/s
+ has_acceleration_limits: true
+ max_acceleration : 2.0 # m/s^2
+ angular:
+ z:
+ has_velocity_limits : true
+ max_velocity : 3.0 # rad/s
+ has_acceleration_limits: true
+ max_acceleration : 3.0 # rad/s^2
<?xml version="1.0"?>
<launch>
+ <!-- Load joint controller configurations from YAML file to parameter server -->
+ <rosparam file="$(find wild_thumper)/config/control.yaml" command="load" />
+
<include file="$(find gazebo_ros)/launch/empty_world.launch" >
<arg name="world_name" value="$(find wild_thumper)/worlds/test.world" />
<arg name="gui" value="false" />
<!-- Spawn a robot into Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model wild_thumper" output="screen" />
+ <!-- load the controllers -->
+ <node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen" ns="/" args="joint_state_controller diff_drive_controller"/>
+
+ <node name="relay_cmd_vel" pkg="topic_tools" type="relay" output="screen" args="/cmd_vel /diff_drive_controller/cmd_vel" />
+ <node name="relay_odom" pkg="topic_tools" type="relay" output="screen" args="/diff_drive_controller/odom /odom" />
+
<node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan" output="screen">
<remap from="/image" to="/camera/depth/image_raw"/>
</node>
+
+ <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
+ <remap from="imu_data" to="imu"/>
+ <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
+ <param name="output_frame" value="odom"/>
+ <param name="freq" value="20.0"/>
+ <param name="vo_used" value="false"/>
+ <param name="debug" value="true"/>
+ <param name="sensor_timeout" value="2.0"/>
+ </node>
</launch>
</geometry>
</visual>
<inertial>
- <mass value="1.9"/>
+ <mass value="2.5"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<axis xyz="0 1 0"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
- </xacro:macro>
- <gazebo reference="front_left_wheel">
- <dampingFactor>0.001</dampingFactor>
- </gazebo>
- <gazebo reference="front_right_wheel">
- <dampingFactor>0.001</dampingFactor>
- </gazebo>
+ <transmission name="${pos}_${side}_wheel_trans" type="SimpleTransmission">
+ <type>transmission_interface/SimpleTransmission</type>
+ <joint name="${pos}_${side}_wheel_joint">
+ <hardwareInterface>VelocityJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="{pos}_${side}_wheel_motor">
+ <hardwareInterface>VelocityJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ </xacro:macro>
- <xacro:wheel pos="aft" side="left" xyz="-0.06398 0.11407 -0.022446" rpy="0 0 0" />
- <xacro:wheel pos="aft" side="right" xyz="-0.07397 -0.11408 -0.022446" rpy="0 0 0" />
- <xacro:wheel pos="front" side="left" xyz="0.07602 0.11407 -0.022446" rpy="0 0 0" />
- <xacro:wheel pos="front" side="right" xyz="0.07397 -0.11408 -0.022446" rpy="0 0 0" />
+ <xacro:wheel pos="rear" side="left" xyz="-0.06398 0.114 -0.022446" rpy="0 0 0" />
+ <xacro:wheel pos="rear" side="right" xyz="-0.07397 -0.114 -0.022446" rpy="0 0 0" />
+ <xacro:wheel pos="front" side="left" xyz="0.07602 0.114 -0.022446" rpy="0 0 0" />
+ <xacro:wheel pos="front" side="right" xyz="0.07397 -0.114 -0.022446" rpy="0 0 0" />
<gazebo>
- <plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
+ <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/</robotNamespace>
- <jointName>aft_left_wheel_joint, aft_right_wheel_joint, front_left_wheel_joint, front_right_wheel_joint</jointName>
- <updateRate>10.0</updateRate>
- <alwaysOn>true</alwaysOn>
+ <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
- <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
- <robotNamespace>/</robotNamespace>
+ <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
<alwaysOn>true</alwaysOn>
- <updateRate>10.0</updateRate>
- <leftJoint>aft_right_wheel_joint</leftJoint>
- <rightJoint>aft_left_wheel_joint</rightJoint>
- <wheelSeparation>0.252</wheelSeparation>
- <wheelDiameter>0.12</wheelDiameter>
- <wheelTorque>5.0</wheelTorque>
- <commandTopic>cmd_vel</commandTopic>
- <odometryTopic>odom</odometryTopic>
- <odometryFrame>odom</odometryFrame>
- <robotBaseFrame>base_footprint</robotBaseFrame>
- <rosDebugLevel>Info</rosDebugLevel>
- <publishWheelTF>false</publishWheelTF>
- <publishWheelJointState>true</publishWheelJointState>
- <wheelAcceleration>0.0</wheelAcceleration>
- <odometrySource>world</odometrySource>
- <publishTf>true</publishTf>
+ <updateRate>20.0</updateRate>
+ <bodyName>base_imu_link</bodyName>
+ <topicName>imu</topicName>
+ <gaussianNoise>0.05</gaussianNoise>
+ <frameName>base_imu_link</frameName>
+ <xyzOffsets>0 0 0</xyzOffsets>
+ <rpyOffset>0 0 0</rpyOffset>
</plugin>
</gazebo>
+
+ <xacro:macro name="range_sensor" params="name ros_topic update_rate minRange maxRange fov radiation">
+ <gazebo reference="${name}">
+ <sensor type="ray" name="${name}_sensor">
+ <pose>0 0 0 0 0 0</pose>
+ <update_rate>${update_rate}</update_rate>
+ <visualize>false</visualize>
+ <ray>
+ <scan>
+ <horizontal>
+ <samples>5</samples>
+ <resolution>1</resolution>
+ <min_angle>-${fov/2}</min_angle>
+ <max_angle>${fov/2}</max_angle>
+ </horizontal>
+ <vertical>
+ <samples>5</samples>
+ <resolution>1</resolution>
+ <min_angle>-${fov/2}</min_angle>
+ <max_angle>${fov/2}</max_angle>
+ </vertical>
+ </scan>
+ <range>
+ <min>${minRange}</min>
+ <max>${maxRange}</max>
+ <resolution>0.01</resolution>
+ </range>
+ </ray>
+ <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
+ <gaussianNoise>0.005</gaussianNoise>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>${update_rate}</updateRate>
+ <topicName>${ros_topic}</topicName>
+ <frameName>${name}</frameName>
+ <fov>${fov}</fov>
+ <radiation>${radiation}</radiation>
+ </plugin>
+ </sensor>
+ </gazebo>
+ </xacro:macro>
+
+ <xacro:range_sensor name="sonar_forward" ros_topic="range_forward" update_rate="10" minRange="0.04" maxRange="6" fov="${60*PI/180}" radiation="ultrasound" />
+ <xacro:range_sensor name="sonar_backward" ros_topic="range_backward" update_rate="10" minRange="0.04" maxRange="6" fov="${60*PI/180}" radiation="ultrasound" />
+ <xacro:range_sensor name="ir_left" ros_topic="range_left" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
+ <xacro:range_sensor name="ir_right" ros_topic="range_right" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
</robot>