Robotics StackExchange | Archived questions

Differential drive robot wheels not attached to body, spawn at 0 0 0

I have created a differential drive robot to learn line following with a camera attached to it. My URDF was working correctly when changeing the innertiavalues of my body parts the wheels seem to spawn at 0 0 0 under the robot. The robot will not move, was moving when the wheels were attached but innertia was wrong. I can't seem to figure out what I am doing wrong . I have tried to change different values to no end. Image from Gazebo image description

The robot model is correct in Rviz image description

Here is my Urdf, I know this is not the most efficient way to do it, but I am hoping i don't need to rewrite using xacro to fix this `<?xml version="1.0"?>

<material name="red">
    <color rgba="0.8 0 0 1"/>
</material>

<material name="blue">
    <color rgba="0 0 0.8 1"/>
</material>

<material name="black">
    <color rgba="0 0 0 1"/>
</material>

<material name="white">
    <color rgba="1 1 1 1"/>
</material>

<link name="base_link">
    <visual>
        <geometry>
            <cylinder length="0.023" radius="0.0825"/>
        </geometry>
        <material name="red"/>
    </visual>
    <collision>
        <geometry>
            <cylinder length="0.023" radius="0.0825"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.1"/>
        <inertia ixx="0.0007" ixy="0.0" ixz="0.0" iyy="0.0007" iyz="0.0" izz="0.0007"/>
    </inertial>
</link>

<link name="base_footprint">
</link>

<joint name="footprint_to_base" type="fixed">
    <parent link="base_footprint"/>
    <child link="base_link"/>
    <origin xyz="0 0 0.06"/>
</joint>

<link name="odom">
</link>

<joint name="footprint_to_odom" type="fixed">
    <parent link="base_footprint"/>
    <child link="odom"/>
    <origin xyz="0 0 0"/>
</joint>

<link name="left_wheel">
    <visual>
        <origin rpy="1.57075 0 0" xyz="0 0 0"/>
        <geometry>
            <cylinder length="0.008" radius="0.035"/>
        </geometry>
        <material name="black"/>
    </visual>
    <collision>
    <avix xyz="0 -1 0" />
    <origin rpy="1.57075 0 0" xyz="-1 0 0"/>
        <geometry>
            <cylinder length="0.008" radius="0.035"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.015"/>
        <inertia ixx="0.00002" ixy="0.0" ixz="0.0" iyy="0.00002" iyz="0.0" izz="0.00002"/>
    </inertial>
</link>

<joint name="base_to_left_wheel" type="continuous">
    <axis xyz="0 1 0" />
    <parent link="base_link"/>
    <child link="left_wheel"/>
    <origin xyz="0 0.0825 0"/>
</joint>

<transmission name="left_wheel_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="base_to_left_wheel">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_wheel_motor">
        <mechanicalReduction>1</mechanicalReduction>
    </actuator>
</transmission> 


<gazebo reference="left_wheel">
    <mu1 value="100000.0"/>
    <mu2 value="3000000.0"/>
    <kp value="10000000.0" />
    <kd value="100000.0" />
    <material>Gazebo/Grey</material>
</gazebo>


<link name="right_wheel">
    <visual>
        <origin rpy="1.57075 0 0" xyz="0 0 0"/>
        <geometry>
            <cylinder length="0.008" radius="0.035"/>
        </geometry>
        <material name="black"/>
    </visual>
    <collision>
    <avix xyz="0 -1 0" />
        <origin rpy="1.57075 0 0" xyz="0 0 0"/>
        <geometry>
            <cylinder length="0.008" radius="0.035"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.015"/>
        <inertia ixx="0.00002" ixy="0.0" ixz="0.0" iyy="0.00002" iyz="0.0" izz="0.00002"/>
    </inertial>
</link>

<joint name="base_to_right_wheel" type="continuous">
    <axis xyz="0 1 0" />
    <parent link="base_link"/>
    <child link="right_wheel"/>
    <origin xyz="0 -0.0825 0"/>
</joint>

<transmission name="right_wheel_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="base_to_right_wheel">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="right_wheel_motor">
        <mechanicalReduction>1</mechanicalReduction>
    </actuator>
</transmission>

<gazebo reference="right_wheel">
    <mu1 value="100000.0"/>
    <mu2 value="3000000.0"/>
    <kp value="10000000.0" />
    <kd value="100000.0" />
    <material>Gazebo/Grey</material>
</gazebo>



<link name="head">
    <visual>
        <geometry>
            <box size="0.03 0.03 0.03"/>
        </geometry>
        <material name="blue"/>
    </visual>
    <collision>
        <geometry>
            <box size="0.03 0.03 0.03"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.02"/>
        <inertia ixx="0.000005" ixy="0.0" ixz="0.0" iyy="0.000005" iyz="0.0" izz="0.000005"/>
    </inertial>
</link>

<joint name="base_to_head" type="fixed">
    <parent link="base_link"/>
    <child link="head"/>
    <origin xyz="0.07 0 0.015"/>
</joint>

<link name="passive_wheel_holder">
    <visual>
        <geometry>
            <cylinder length="0.02" radius="0.015"/>
        </geometry>
        <material name="white"/>
    </visual>
    <collision>
        <geometry>
            <cylinder length="0.02" radius="0.015"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.02"/>
        <inertia ixx="0.000005" ixy="0.0" ixz="0.0" iyy="0.000005" iyz="0.0" izz="0.000005"/>
    </inertial>
</link>

<joint name="base_to_passive_wheel_holder" type="fixed">
    <parent link="base_link"/>
    <child link="passive_wheel_holder"/>
    <origin xyz="0.07 0 -0.01"/>
</joint>

<link name="passive_wheel">
    <visual>
        <geometry>
            <sphere radius="0.015"/>
        </geometry>
        <material name="white"/>
    </visual>
    <collision>
        <geometry>
            <sphere radius="0.015"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.02"/>
        <inertia ixx="0.000005" ixy="0.0" ixz="0.0" iyy="0.000005" iyz="0.0" izz="0.000005"/>
    </inertial>
</link>

<gazebo reference="passive_wheel">
    <mu1 value="0.0"/>
    <mu2 value="0.0"/>
    <kp value="1000.0" />
    <kd value="1000.0" />
    <slip1>1.0</slip1>
    <slip2>1.0</slip2>
    <material>Gazebo/Grey</material>
</gazebo>

<joint name="passive_wheel_holder_to_passive_wheel" type="fixed">
    <parent link="passive_wheel_holder"/>
    <child link="passive_wheel"/>
    <origin xyz="0  0 -0.01"/>
</joint>

<link name = "camera">
     <visual>
        <geometry>
            <box size="0.02 0.02 0.02"/>
        </geometry>
        <material name="white"/>
    </visual>
    <collision>
        <geometry>
            <box size="0.02 0.02 0.02"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.01"/>
        <inertia ixx="0.000001" ixy="0.0" ixz="0.0" iyy="0.000001" iyz="0.0" izz="0.000001"/>
    </inertial>
</link>

<joint name="camera_to_head" type="fixed">
    <origin xyz = "0 0 0.025"/>
    <parent link = "head"/>
    <child link = "camera"/>
</joint>

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/</robotNamespace>
        <legacyModeNS>true</legacyModeNS>
    </plugin>
    <plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
        <jointName>base_to_left_wheel, base_to_right_wheel</jointName>
    </plugin>
    <plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>50.0</updateRate>
        <bodyName>base_link</bodyName>
        <topicName>ground_truth</topicName>
        <gaussianNoise>0.01</gaussianNoise>
        <frameName>map</frameName>
        <xyzOffsets>0 0 0</xyzOffsets>
        <rpyOffsets>0 0 0</rpyOffsets>
    </plugin>
</gazebo>

<!-- camera --> 30.0 1.3962634 800 800 R8G8B8enter code here 0.02 300 gaussian 0.0 0.007 true 0.0 differentialrobot/camera imageraw camera_info camera 0.07 0.0 0.0 0.0 0.0 0.0

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/differential_robot_cam</robotNamespace>
        <legacyModeNS>true</legacyModeNS>
    </plugin>
</gazebo>

`

And This is my launch file to run everything except the line following algorithm

<include file="$(find differential_robot_line_186105iacb)/launch/gazebo.launch">
    <arg name="model" value="$(arg model)" />
</include>

<node name="transform" pkg="transform_frame" type="move">
    <remap from="/cmd_vel" to="diff_drive_controller/cmd_vel"/>
</node>

<rosparam command="load"
    file="$(find differential_robot_line_186105iacb)/config/joints.yaml"
    ns="joint_state_controller" />
<rosparam command="load"
    file="$(find differential_robot_line_186105iacb)/config/diffdrive.yaml"
    ns="diff_drive_controller" />

<node name="controller_spawner" pkg="controller_manager" type="spawner"
    args="
        joint_state_controller 
        diff_drive_controller
        --shutdown-timeout 3"/>

<node name="teleop_twist_keyboard" pkg="teleop_twist_keyboard" type="teleop_twist_keyboard.py">
</node>

<node name="rqt_robot_steering" pkg="rqt_robot_steering" type="rqt_robot_steering">
    <param name="default_topic" value="diff_drive_controller/cmd_vel"/>
</node>

Asked by MASTERLLAMACHEESE on 2020-12-22 10:28:25 UTC

Comments

Answers

Update: Seems to be an issue with intertia, as the inertia for the wheel can't be set below 0.5kg*m^2, but i need my wheel mass to be 0.015kg, setting the inertia values to what they are supposed to be using calculations from here . Makes wheels spawn at 0 0 0 and the robot to not function properly also error [param.cc:451] stated to appear when trying to fix. Still looking for solution and or suggestions from here.

Asked by MASTERLLAMACHEESE on 2021-01-05 07:17:08 UTC

Comments