Robotics StackExchange | Archived questions

Snake-Robot is not moving at any direction no matter what I do or change

image description

Hello, I've been working on this snake robot simulation in gazebo, I succeeded in making the robot take the sin wave form which it should. In order to make the robot move forward you need to change the value of the coefficients of all the links to produce propulsive force. The problem is that no matter how many different values I try out, It just won't move not only forward but in any direction for that matter. It just won't budge.

Also I don't know if you can deduce it from the photo but for some reason the first link is not rotating with the other links as it should. It should be rotating as it's connected to the first joint and the first joint is rotating. I tried applying forces using the apply force option of gazebo and everything moves so the links are not fixed in place.

Xacro file contents:

<?xml version="1.0"?>

<xacro:include filename="inertial_macros.xacro"/>
<xacro:include filename="materials.xacro"/> 
<xacro:include filename="ros2_control.xacro" />
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>




<!-- JOINT BETWEEN THE TAIL AND THE FIRST LINK -->

<joint name="link_head_1_joint" type="revolute">
    <parent link="head_link"/>
    <child link="link_1"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
 <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!-- LINK 1 -->

     <!-- TAIL LINK WHICH I HAVE CALLED FOR HEAD LINK -->
<link name="head_link">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
  <inertial>
  <mass value="0.1"/>
  <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
</inertial>
</link>

<link name="link_1">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
         <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>       
 <inertial>
  <mass value="0.1"/>
  <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
</inertial>
</link>



<!-- JOINT BETWEEM LINK 1 AND 2 -->

<joint name="link_1_2_joint" type="revolute">
    <parent link="link_1"/>
    <child link="link_2"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>  
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!-- LINK 2 -->

<link name="link_2">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>           
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>
</link>   



<!--JOINT BETWEEN LINK 2 AND LINK 3 -->

<joint name="link_2_3_joint" type="revolute">
    <parent link="link_2"/>
    <child link="link_3"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!-- LINK 3 -->

<link name="link_3">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>
</link>


<!-- JOINT BETWEEN LINK 3 AND LINK 4 ***NOTE THAT LINK 4 IS THE HEAD -->

<joint name="link_3_4_joint" type="revolute">
    <parent link="link_3"/>
    <child link="link_4"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!-- LINK 4-->

<link name="link_4">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>  
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>
</link>


<!-- JOINT BETWEEN LINK 4 AND LINK 5 ***NOTE THAT LINK 4 IS THE HEAD -->

<joint name="link_4_5_joint" type="revolute">
    <parent link="link_4"/>
    <child link="link_5"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!--  LINK 5-->

<link name="link_5">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>  
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>
</link>

<!-- JOINT BETWEEN LINK 5 AND LINK 6 ***NOTE THAT LINK 4 IS THE HEAD -->

<joint name="link_5_6_joint" type="revolute">
    <parent link="link_5"/>
    <child link="link_6"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!--  LINK 6-->

<link name="link_6">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>  
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>
</link>


<!-- JOINT BETWEEN LINK 6 AND LINK 7 ***NOTE THAT LINK 4 IS THE HEAD -->

<joint name="link_6_7_joint" type="revolute">
    <parent link="link_6"/>
    <child link="link_7"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!--  LINK 7-->

<link name="link_7">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>  
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>
</link>


<!-- JOINT BETWEEN LINK 7 AND LINK 8 ***NOTE THAT LINK 4 IS THE HEAD -->

<joint name="link_7_8_joint" type="revolute">
    <parent link="link_7"/>
    <child link="link_8"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!--  LINK 8-->

<link name="link_8">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>  
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>
</link>

<!-- JOINT BETWEEN LINK 8 AND LINK 9 ***NOTE THAT LINK 4 IS THE HEAD -->

<joint name="link_8_9_joint" type="revolute">
    <parent link="link_8"/>
    <child link="link_9"/>
    <limit lower="-1.5708" upper="1.5708" velocity="4.0" effort="1000.0"/>
    <origin xyz="0.0 0.1 0.0" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <!--   <joint_properties damping="2.0" friction="2.0"/>  -->
</joint>

<!--  LINK 9-->

<link name="link_9">
    <visual>

        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>  
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0.0 0.035 0.02" rpy="0.0 0.0 0.0"/>
        <geometry>
            <box size="0.04 0.07 0.04"/>
        </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
        <inertia ixx="0.00005416666" ixy="0.0" ixz="0.0" iyy="0.00002666666" iyz="0.0" izz="0.00005416666"/>
    </inertial>

</link>

Any help or thoughts would be very much appreciated in this matter.

Asked by BLueShadow on 2023-03-19 13:13:25 UTC

Comments

Answers

Found an alternative way, the problem was with the controller that I was using which is the jointgrouppositioncontroller, For some unknown reason it doesn't cause the joints to move or exert any type of force which is very much weird and counter-intuitive. When I changed the controller to Effort/Forward controllers it moved like it was supposed to.

Asked by BLueShadow on 2023-04-01 11:12:30 UTC

Comments