ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

how to make a joint rotate a specified angle

asked 2011-09-04 14:11:33 -0500

shenhaobin gravatar image

updated 2011-09-07 07:58:46 -0500

Wim gravatar image

Hello,everyone! I am a novice in gazebo. I want to simulate my robot arm in gazebo. Here is part of my urdf file.


<?xml version="1.0" ?>
<robot name="jixiebi">
    <link name="arm1">
        <visual>
            <geometry>
                <mesh filename="arm - arm1-1.STL"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0.00039 -0.00037 0.0"/>
            <material name="arm1_color">
                <color rgba="0.752941 0.752941 0.752941 1"/>
            </material>
        </visual>
        <collision>
            <geometry>
                <mesh filename="arm - arm1-1.STL"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0.00039 -0.00037 0.0"/>
        </collision>
        <inertial>
            <mass value="1.04075"/>
            <inertia ixx="0.004368" ixy="-0.00001" ixz="0.000002" iyy="0.004367" iyz="-0.000001" izz="0.002456"/>
            <origin rpy="0 0 0" xyz="0.000393 -0.000373 -0.074418"/>
        </inertial>
    </link>
    <joint name="arm1-arm2" type="continuous">
        <limit effort="1000.0" lower="-3.1415926" upper="3.1415926" velocity="0.5"/>
        <dynamics damping="0.0" friction="0.0"/>
        <parent link="arm1"/>
        <child link="arm2"/>
        <origin rpy="0 0 0" xyz="0 0 0.173"/>
        <axis xyz="0 0 1"/>
    </joint>
    <link name="arm2">
        <visual>
            <geometry>
                <mesh filename="arm - arm2-1.STL"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="arm2_color">
                <color rgba="0.752941 0.752941 0.752941 1"/>
            </material>
        </visual>
        <collision>
            <geometry>
                <mesh filename="arm - arm2-1.STL"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0.0"/>
        </collision>
        <inertial>
            <mass value="1.26789"/>
            <inertia ixx="0.003947" ixy="-0.000001" ixz="-0.000617" iyy="0.006723" iyz="-0.000004" izz="0.005568"/>
            <origin rpy="0 0 0" xyz="-0.100667 0.000085 -0.013708"/>
        </inertial>
    </link>
    <joint name="arm2-arm3" type="continuous">
        <limit effort="1000.0" lower="-3.1415926" upper="3.1415926" velocity="0.5"/>
        <dynamics damping="0.0" friction="0.0"/>
        <parent link="arm2"/>
        <child link="arm3"/>
        <origin rpy="0 0 0" xyz="0.084 0 0.107"/>
        <axis xyz="1 0 0"/>
    </joint>
    <link name="arm3">
        <visual>
            <geometry>
                <mesh filename="arm - arm3-1.STL"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="arm3_color">
                <color rgba="0.752941 0.752941 0.752941 1"/>
            </material>
        </visual>
        <collision>
            <geometry>
                <mesh filename="arm - arm3-1.STL"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
        </collision>
        <inertial>
            <mass value="0.65756"/>
            <inertia ixx="0.002035" ixy="-0.000006" ixz="-0.000239" iyy="0.002506" iyz="-0" izz="0.001401"/>
            <origin rpy="0 0 0" xyz="0.156093 0.000249 0.270754"/>
        </inertial>
    </link>
    <gazebo reference="arm1">
        <material>Gazebo/White</material>
        <turnGravityOff>false</turnGravityOff>
        <selfCollide>true</selfCollide>
    </gazebo>
    <gazebo reference="arm1-arm2">
        <stopKd value="1.0"/>
        <stopKp value="1000000.0"/>
        <fudgeFactor value="0.5"/>
    </gazebo>
    <gazebo reference="arm2">
        <material>Gazebo/White</material>
        <turnGravityOff>true</turnGravityOff>
        <selfCollide>true</selfCollide>
    </gazebo> 
    <gazebo reference="arm2-arm3">
        <stopKd value="1.0"/>
        <stopKp value="1000000.0"/>
        <fudgeFactor value="0.5"/>
    </gazebo>
    <gazebo reference="arm3">
        <material>Gazebo/White</material>
        <turnGravityOff>true</turnGravityOff>
        <selfCollide>true</selfCollide>
    </gazebo>  
</robot>

I have a c++ program that can calculate the value of the angle to rotate when you specify a goal position. So my ... (more)

edit retag flag offensive close merge delete

3 Answers

Sort by » oldest newest most voted
3

answered 2011-09-11 13:14:25 -0500

Wim gravatar image

The URDF simply describes the kinematic and dynamic properties of your robot mechanism. If you want to make a joint rotate a specific angle, you need to write a controller that commands the joint to do something. The controller will probably monitor the joint position, and command joint efforts or velocities. See the robot mechanism controllers wiki page for examples of controllers that run in the pr2 controller infrastructure.

edit flag offensive delete link more
4

answered 2011-09-11 23:59:21 -0500

To expand on @Wim's answer, one example of using the pr2 controller infrastructure is here: pr2_arm_gazebo. It can easily be used on a non-PR2 arm, too. Here are the most important things you'll have to do (from pr2_arm_gazebo):

URDF file:

<gazebo>
  <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so">
    <alwaysOn>true</alwaysOn>
    <updateRate>1000.0</updateRate>
  </controller:gazebo_ros_controller_manager>
</gazebo>

Also, your URDF file needs transmissions for each joint, otherwise the pr2_controller_manager won't work.

Launch file:

...

<!-- Default Controllers -->
<rosparam command="load" file="$(find pr2_controller_configuration_gazebo)/pr2_arm_controllers.yaml" />

<!-- Controller Manager -->
<include file="$(find pr2_controller_manager)/controller_manager.launch" />

<!-- Controllers that come up loaded -->
<node name="default_loaded_controllers_spawner"
      pkg="pr2_controller_manager" type="spawner" output="screen"
      args="--wait-for=/calibrated r_arm_controller" />

<!-- Fake calibration -->
<node pkg="rostopic" type="rostopic" name="fake_joint_calibration"
      args="pub /calibrated std_msgs/Bool true" />

...

pr2_arm_controllers.yaml:

 r_arm_controller:
   type: "robot_mechanism_controllers/JointTrajectoryActionController"
   joints:
     - r_shoulder_pan_joint
     - r_shoulder_lift_joint
     - r_upper_arm_roll_joint
     - r_elbow_flex_joint
     - r_forearm_roll_joint
     - r_wrist_flex_joint
     - r_wrist_roll_joint
   gains:
     r_shoulder_pan_joint: {p: 2400.0, d: 18.0, i: 800.0, i_clamp: 4.0}
     r_shoulder_lift_joint: {p: 1200.0, d: 10.0, i: 700.0, i_clamp: 4.0}
     r_upper_arm_roll_joint: {p: 1000.0, d: 6.0, i: 600.0, i_clamp: 4.0}
     r_elbow_flex_joint: {p: 700.0, d: 4.0, i: 450, i_clamp: 4.0}
     r_forearm_roll_joint: {p: 300.0, d: 6.0, i: 300, i_clamp: 2.0}
     r_wrist_flex_joint: {p: 300.0, d: 4.0, i: 300, i_clamp: 2.0}
     r_wrist_roll_joint: {p: 300.0, d: 4.0, i: 300, i_clamp: 2.0}
   joint_trajectory_action_node:
     joints:
       - r_shoulder_pan_joint
       - r_shoulder_lift_joint
       - r_upper_arm_roll_joint
       - r_elbow_flex_joint
       - r_forearm_roll_joint
       - r_wrist_flex_joint
       - r_wrist_roll_joint
     constraints:
       goal_time: 0.6
       r_shoulder_pan_joint:
         goal: 0.02
       r_shoulder_lift_joint:
         goal: 0.02
       r_upper_arm_roll_joint:
         goal: 0.02
       r_elbow_flex_joint:
         goal: 0.02
       r_forearm_roll_joint:
         goal: 0.02
       r_wrist_flex_joint:
         goal: 0.02
       r_wrist_roll_joint:
         goal: 0.02

Now you'll have to send trajectories to the arm and experiment to find the right PID parameters. (Hint: they'll probably be rather in the range of 0-10 if you use a transmission mechanical reduction of 1).

edit flag offensive delete link more
0

answered 2011-09-05 15:03:30 -0500

JonW gravatar image

updated 2011-09-05 15:05:39 -0500

From looking at your joint description you have set the damping and friction values of the joints to zero. With no friction, once a torque is applied the joint will rotate until a counteracting torque is applied.

Likewise with the joint between arm2 and arm3 has no friction. Thus with no torque and no friction to hold the relative position, the joint will rotate due to the mass of the arm3 link.

I would suggest adding some friction to the joints and seeing if this resolves your problem.

edit: just realised you want a specific angle - I expect you will need some form of PID feedback controller to generate the joint effort required to reach your goal angle.

edit flag offensive delete link more

Comments

I believe ODE doesn't support friction on joints, so unless you load a controller that takes care of friction, setting joint friction values in the URDF will not have any effect.
Lorenz gravatar image Lorenz  ( 2011-09-12 00:52:04 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2011-09-04 14:11:33 -0500

Seen: 4,570 times

Last updated: Sep 11 '11