I am simulating a robot arm, at the end of which a freely moving cylinder is supposed to be attached.
I am trying to simulate, a robotic arm, which is controlled by the arm_controller , this robotic arm is similar to the chapter 18 of the Programming Robots with Ros book.
The problem is I wanted the link at the end (hand) to act freely due to gravity and it does not act freely, instead its position keeps fixed relative to the link it is attached with.
I have removed the transmittion information for this hand in the URDF file and also from the controllers.YAML
controllers.YAML is below
arm_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- hip
- shoulder
- elbow
Following is my URDF file
<?xml version="1.0"?>
<robot name="cougarbot">
<link name="world"/>
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<material name="silver">
<color rgba="0.75 0.75 0.75 1"/>
</material>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</collision>
<inertial>
<mass value="1.0"/>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
<inertia ixx="0.0027" iyy="0.0027" izz="0.005" ixy="0" ixz="0" iyz="0"/>
</inertial>
</link>
<joint name="fixed" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>
<link name="torso">
<visual>
<geometry>
<cylinder length="0.2" radius="0.05"/>
</geometry>
<material name="silver">
<color rgba="0.75 0.75 0.75 1"/>
</material>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
</visual>
<collision>
<geometry>
<cylinder length="0.2" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
</collision>
<inertial>
<mass value="1.0"/>
<origin rpy="0 0 0" xyz="0 0 0.25"/>
<inertia ixx="0.02146" iyy="0.02146" izz="0.00125" ixy="0" ixz="0" iyz="0"/>
</inertial>
</link>
<joint name="hip" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="torso"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.05"/>
</joint>
<link name="upper_arm">
<visual>
<geometry>
<cylinder length="0.2" radius="0.05"/>
</geometry>
<material name="silver"/>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
</visual>
<collision>
<geometry>
<cylinder length="0.2" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
</collision>
<inertial>
<mass value="0.2"/>
<origin rpy="0 0 0" xyz="0 0 0.2"/>
<inertia ixx="0.01396" iyy="0.01396" izz="0.00125" ixy="0" ixz="0" iyz="0"/>
</inertial>
</link>
<joint name="shoulder" type="continuous">
<axis xyz="0 1 0"/>
<parent link="torso"/>
<child link="upper_arm"/>
<origin rpy="0 1.5708 0" xyz="0.0 -0.1 0.15"/>
</joint>
<link name="lower_arm">
<visual>
<geometry>
<cylinder length="0.2" radius="0.05"/>
</geometry>
<material name="silver"/>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
</visual>
<collision>
<geometry>
<cylinder length="0.2" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
</collision>
<inertial>
<mass value="0.2"/>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<inertia ixx="0.01396" iyy="0.01396" izz="0.00125" ixy="0" ixz="0" iyz="0"/>
</inertial>
</link>
<joint name="elbow" type="continuous">
<axis xyz="0 1 0"/>
<parent link="upper_arm"/>
<child link="lower_arm"/>
<origin rpy="0 0 0" xyz="0.0 0.1 0.15"/>
</joint>
<link name="hand">
<visual>
<geometry>
<cylinder length="2.0" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 1.0"/>
<material name="silver"/>
</visual>
<collision>
<geometry>
<cylinder length="2.0" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 1.0"/>
</collision>
<inertial>
<mass value="2.0"/>
<inertia ixx="0.01396" iyy="100" izz="0.00125" ixy="0" ixz="0" iyz="0"/>
</inertial>
</link>
<joint name="wrist" type="continuous">
<axis xyz="0 1 0"/>
<parent link="lower_arm"/>
<child link="hand"/>
<origin rpy="0 0 0" xyz="0.0 -0.1 0.225"/>
<dynamics damping="0.0"/>
</joint>
<transmission name="tran0">
<type>transmission_interface/SimpleTransmission</type>
<joint name="hip">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor0">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="elbow">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor2">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo>
<plugin name="control" filename="libgazebo_ros_control.so"/>
</gazebo>
<gazebo>
<plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
<jointName>hip, shoulder, elbow ,wrist</jointName>
</plugin>
</gazebo>
</robot>
Since we are not controlling the movement of the last link (hand) it is supposed to fall down, but it does not.
Apart from that I also changed the settings via Moveit. I removed the wrist joint from active joints, by putting wrist joint into passive joints.
I moved the endeffector from hand to lower arm. Even after that the last link , does not fall upon gravity. Somehow its position is fixed. I would really appreciate insight into this problem.
Screenshot from 2016-05-24 10:41:34.png
Asked by Abdullah on 2016-05-24 11:06:37 UTC
Answers
When simulating your arm in Gazebo, the wrist
joint connecting the lower arm to the hand is acting as a constraint on the movement, only allowing it to rotate in one axis (Y axis). It sounds like you would like a "ball joint" behavior, which is a constraint on all translation DOF, but all the rotation DOF can rotate freely.
URDF doesn't seem to support ball joints. You could try to fake it by adding more joints and pseudo-links as mentioned here.
Asked by chapulina on 2016-05-24 16:14:38 UTC
Comments
Thank you so much for responding so early and so quickly. I really appreciate that. But even when we have one degree freedom, it should fall down to the ground by rotating on this axis. There might be some other problem?
Asked by Abdullah on 2016-05-24 16:38:28 UTC
Oh ok sorry, then I completely misinterpreted what you were saying. What version of Gazebo are you using?
Asked by chapulina on 2016-05-24 16:41:49 UTC
Continuous joints are revolute joints without limits. Perhaps you are looking for behaviors of a prismatic joint?
Asked by hsu on 2016-05-24 16:48:53 UTC
I recently installed Gazebo, and I do not know the version. I really appreciate your interest.
Asked by Abdullah on 2016-05-24 16:50:25 UTC
Dear Hsu, Thank you so much for the help, the thing is , the problem is not about the degree of freedoms, there is one degree of freedom and its ok, and it can rotate around y-axis. The problem is that the link hand is not falling down because of gravity. Is it because I am using position based control?
Asked by Abdullah on 2016-05-24 16:52:23 UTC
Yes, the position based control (e.g. https://github.com/ros-simulation/gazebo_ros_pkgs/blob/jade-devel/gazebo_ros_control/src/default_robot_hw_sim.cpp#L300) will negate dynamics (i.e. ignore gravity or external forces)
Asked by hsu on 2016-05-25 18:38:49 UTC
Comments