Problem with propellers rotating around middle of robot.
I am making a quadcopter and the propellers are rotating around the center of the robot. I am trying to get the propellers to be stationary and just rotate in place. I have added some pictures of before and during rotation to show the problem. Below is the code I am using. Any help would be appreciated.
<?xml version="1.0"?>
<material name="magenta">
<color rgba="1 .1 .85 1"/>
</material>
<link name="dummy">
<link name="base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.5 0.5 0.5"/>
</geometry>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.2 0.2 0.1"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="propeller_M1_link">
<inertial>
<origin rpy="0.0 0 0" xyz="0.25 0 0.0422"/>
<mass value="0.1" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0.0 0 0" xyz="0.25 0 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0.25 0 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="arm_M1_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.18" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0.175 0 0"/>
<geometry>
<box size="0.15 0.05 0.05"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0.175 0 0"/>
<geometry>
<box size="0.15 0.05 0.05"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="motor_M1_link">
<inertial>
<origin rpy="0.0 0 0" xyz="0.25 0 0.0255"/>
<mass value="0.1" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0.0 0 0" xyz="0.25 0 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="0.25 0 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="propeller_M2_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.25 0 0.0422"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
<mass value="0.1"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="-0.25 0 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="-0.25 0 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="arm_M2_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.18" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="-0.175 0 0"/>
<geometry>
<box size="0.15 0.05 0.05"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="-0.175 0 0"/>
<geometry>
<box size="0.15 0.05 0.05"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="motor_M2_link">
<inertial>
<origin rpy="0.0 0 0" xyz="-0.25 0 0.0255"/>
<mass value="0.1" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0.0 0 0" xyz="-0.25 0 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0.0 0 0" xyz="-0.25 0 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="propeller_M3_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0.25 0.0422"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
<mass value="0.1"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0.25 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0.25 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="arm_M3_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.18" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0.175 0"/>
<geometry>
<box size="0.05 0.15 0.05"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0.175 0"/>
<geometry>
<box size="0.05 0.15 0.05"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="motor_M3_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0.25 0.0255"/>
<mass value="0.1" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0.25 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0.25 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="propeller_M4_link">
<inertial>
<origin rpy="0 0 0" xyz="0 -0.25 0.0422"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
<mass value="0.1"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 -0.25 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 -0.25 0.0422"/>
<geometry>
<cylinder radius="0.06" length="0.0324"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="arm_M4_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.18" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 -0.175 0"/>
<geometry>
<box size="0.05 0.15 0.05"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 -0.175 0"/>
<geometry>
<box size="0.05 0.15 0.05"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<link name="motor_M4_link">
<inertial>
<origin rpy="0 0 0" xyz="0 -0.25 0.0255"/>
<mass value="0.1" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 -0.25 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 -0.25 0.0255"/>
<geometry>
<cylinder radius="0.006" length="0.001"/>
</geometry>
<material name="magenta"/>
</visual>
</link>
<joint name="arm_base_M1_joint" type="fixed">
<parent link="base_link"/>
<child link="arm_M1_link"/>
<!-- <origin xyz="0.125 0 0" rpy="0 0 0"/> -->
</joint>
<joint name="arm_base_M2_joint" type="fixed">
<parent link="base_link"/>
<child link="arm_M2_link"/>
<!-- <origin xyz="-0.125 0 0" rpy="0 0 0"/> -->
</joint>
<joint name="arm_base_M3_joint" type="fixed">
<parent link="base_link"/>
<child link="arm_M3_link"/>
<!-- <origin xyz="0 0.125 0" rpy="0 0 0"/> -->
</joint>
<joint name="arm_base_M4_joint" type="fixed">
<parent link="base_link"/>
<child link="arm_M4_link"/>
<!-- <origin xyz="0 -0.125 0" rpy="0 0 0"/> -->
</joint>
<joint name="motor_arm_M1_joint" type="revolute">
<parent link="arm_M1_link"/>
<child link="motor_M1_link"/>
<limit effort="0" lower="-0.0" upper="0.0" velocity="0"/>
<!-- <origin xyz="0 -0.125 0" rpy="0 0 0"/> -->
</joint>
<joint name="motor_arm_M2_joint" type="revolute">
<parent link="arm_M2_link"/>
<child link="motor_M2_link"/>
<limit effort="0" lower="-0.0" upper="0.0" velocity="0"/>
<!-- <origin xyz="0 -0.125 0" rpy="0 0 0"/> -->
</joint>
<joint name="motor_arm_M3_joint" type="revolute">
<parent link="arm_M3_link"/>
<child link="motor_M3_link"/>
<limit effort="0" lower="-0.0" upper="0.0" velocity="0"/>
<!-- <origin xyz="0 -0.125 0" rpy="0 0 0"/> -->
</joint>
<joint name="motor_arm_M4_joint" type="revolute">
<parent link="arm_M4_link"/>
<child link="motor_M4_link"/>
<limit effort="0" lower="-0.0" upper="0.0" velocity="0"/>
<!-- <origin xyz="0 -0.125 0" rpy="0 0 0"/> -->
</joint>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/drone</robotNamespace>
</plugin>
</gazebo>
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="propeller_arm_M1_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="propeller_arm_M2_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor2">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran3">
<type>transmission_interface/SimpleTransmission</type>
<joint name="propeller_arm_M3_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor3">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran4">
<type>transmission_interface/SimpleTransmission</type>
<joint name="propeller_arm_M4_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor4">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- <gazebo reference="base_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="propeller_M1_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="propeller_M2_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="propeller_M3_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="propeller_M4_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="arm_M1_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="arm_M2_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="arm_M3_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="arm_M4_link">
<material>Gazebo/Blue</material>
</gazebo> -->
Asked by Resilient System Laboratory on 2020-01-15 12:52:22 UTC
Comments