How to implement the Skid Steering Drive plugin in Gazebo and why do I not need transmission tags?
Hello, I'm new to Gazebo and ROS and wanted to implement the skid steering plugin from Gazebo for the a very basic 4 wheeled 'robot' , but I'm not sure what how the axis are supposed to be set and what some of the requiried variables truly mean e.g torque (not sure which number I should give as input) or broadcastTF (not sure why I should not want to broadcast) . At the moment I can drive backwards and forwards but it the robot does not turn. Here is the xacro that I'm using at the moment:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="base1">
<!-- variables-->
<xacro:property name="length_wheel" value="0.1"/>
<xacro:property name="radius_wheel" value="0.2"/>
<xacro:property name="base_heigth" value="0.3"/>
<xacro:property name="base_width" value="0.6"/>
<xacro:property name="base_length" value="1.0"/>
<xacro:property name="hokuyo_box_size" value="0.05"/>
<xacro:property name="camera_box_size" value="0.05"/>
<!--<xacro::property name="offset" value=""/>-->
<xacro:property name="PI" value="3.14159265359"/>
<!-- Gazebo colors -->
<xacro:include filename="$(find own_base)/urdf/base1.gazebo"/>
<!-- macros-->
<xacro:macro name="default_inertial" params="mass">
<inertial>
<mass value="${mass}"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</xacro:macro>
<link name="base">
<visual>
<geometry>
<box size="${base_length} ${base_width} ${base_heigth}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="${base_length} ${base_width} ${base_heigth}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<xacro:default_inertial mass="100"/>
</link>
<link name="wheele_1">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<origin xyz="0 0 0" rpy="0 0 0"/>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<xacro:default_inertial mass="5"/>
</link>
<link name="wheele_2">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<xacro:default_inertial mass="5"/>
</link>
<link name="wheele_3">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<xacro:default_inertial mass="5"/>
</link>
<link name="wheele_4">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<xacro:default_inertial mass="5"/>
</link>
<link name="hokuyo_link">
<visual>
<geometry>
<box size="${hokuyo_box_size} ${hokuyo_box_size} ${hokuyo_box_size}"/>
</geometry ...