0
$\begingroup$

Rosanswers logo

Hy guys,

I have a Slider-Crank like mechanism to control.

How can I represent/write under URDF notation a bearing which is connected to a link and slides inside a prismatic joint? It's possible to represent that "crank joint"?

thank you!


Originally posted by Bemfica on ROS Answers with karma: 482 on 2011-09-02

Post score: 1

$\endgroup$

3 Answers 3

0
$\begingroup$

Rosanswers logo

yes it's possible, you can lay out the links and joints as shown in the animation you've linked above. Here's one that has both ends weighted down by gravity.

<robot name="crank">
  <link name="link1"> <!-- left most red link in the animation -->
    <inertial>
      <mass value="100.0" />
      <!-- center of mass (com) is defined w.r.t. link local coordinate system -->
      <origin xyz="0 0 0" /> 
      <inertia  ixx="10.0" ixy="0.0"  ixz="0.0"  iyy="10.0"  iyz="0.0"  izz="10.0" />
    </inertial>
    <visual>
      <origin xyz="0 0 0.25" rpy="0 0 0" />
      <geometry>
        <box size="0.1 0.1 0.5"/>
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 0 0.025" rpy="0 0 0" />
      <geometry>
        <box size="1.0 1.0 0.05"/>
      </geometry>
    </collision>
  </link>
  <joint name="link1_link2_joint" type="continuous">
    <parent link="link1" />
    <child link="link2" />
    <origin xyz="0 0 0.5" rpy="0 0 0" />
    <axis xyz="0 1 0"/>
  </joint>
  <link name="link2"> <!-- blue link in the animation -->
    <inertial>
      <mass value="1.0" />
      <!-- center of mass (com) is defined w.r.t. link local coordinate system -->
      <origin xyz="0.1 0 0" /> 
      <inertia  ixx="0.01" ixy="0.0"  ixz="0.0"  iyy="0.01"  iyz="0.0"  izz="0.01" />
    </inertial>
    <visual>
      <origin xyz="0.1 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.2 0.05 0.05"/>
      </geometry>
    </visual>
    <collision>
      <origin xyz="0.1 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.2 0.05 0.05"/>
      </geometry>
    </collision>
  </link>
  <joint name="link2_link3_joint" type="continuous">
    <parent link="link2" />
    <child link="link3" />
    <origin xyz="0.2 0 0" rpy="0 0 0" />
    <axis xyz="0 1 0"/>
  </joint>
  <link name="link3"> <!-- red sliding link in the animation -->
    <inertial>
      <mass value="1.0" />
      <origin xyz="0.25 0 0" /> 
      <inertia  ixx="0.01" ixy="0.0"  ixz="0.0"  iyy="0.01"  iyz="0.0"  izz="0.01" />
    </inertial>
    <visual>
      <origin xyz="0.25 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.5 0.05 0.05"/>
      </geometry>
    </visual>
    <collision>
      <origin xyz="0.25 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.5 0.05 0.05"/>
      </geometry>
    </collision>
  </link>
  <joint name="link3_link4_joint" type="continuous">
    <parent link="link3" />
    <child link="link4" />
    <origin xyz="0.5 0 0" rpy="0 0 0" />
    <axis xyz="0 1 0"/>
  </joint>
  <link name="link4"> <!-- right most gray link in the animation -->
    <inertial>
      <mass value="1.0" />
      <origin xyz="0 0 0" /> 
      <inertia  ixx="0.01" ixy="0.0"  ixz="0.0"  iyy="0.01"  iyz="0.0"  izz="0.01" />
    </inertial>
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <sphere radius="0.1"/>
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <sphere radius="0.1"/>
      </geometry>
    </collision>
  </link>
  <joint name="link4_link5_joint" type="prismatic">
    <parent link="link4" />
    <child link="link5" />
    <origin xyz="0 0 0" rpy="0 0 0" />
    <axis xyz="1 0 0"/>
    <limit upper="0.4" lower="0" effort="1000.00" velocity="1000.00"/>
  </joint>
  <link name="link5"> <!-- right most gray link in the animation -->
    <inertial>
      <mass value="100.0" />
      <origin xyz="0 0 0" /> 
      <inertia  ixx="10.0" ixy="0.0"  ixz="0.0"  iyy="10.0"  iyz="0.0"  izz="10.0" />
    </inertial>
    <visual>
      <origin xyz="-0.2 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.4 0.1 0.1"/>
      </geometry>
    </visual>
    <collision>
      <origin xyz="0 0 -0.475" rpy="0 0 0" />
      <geometry>
        <box size="1.0 1.0 0.05"/>
      </geometry>
    </collision>
  </link>
  <gazebo reference="link1">
    <turnGravityOff>false</turnGravityOff>
    <material>Gazebo/Red</material>
  </gazebo>
  <gazebo reference="link2">
    <turnGravityOff>true</turnGravityOff>
    <material>Gazebo/Blue</material>
  </gazebo>
  <gazebo reference="link3">
    <turnGravityOff>true</turnGravityOff>
    <material>Gazebo/Red</material>
  </gazebo>
  <gazebo reference="link4">
    <turnGravityOff>true</turnGravityOff>
    <material>Gazebo/Blue</material>
  </gazebo>
  <gazebo reference="link5">
    <turnGravityOff>false</turnGravityOff>
    <material>Gazebo/Gray</material>
  </gazebo>
</robot>

Apply torque to see it rotate

rosservice call  /gazebo/apply_joint_effort '{joint_name: link1_link2_joint, effort: 10, start_time: 0, duration: 10000000}'

Originally posted by hsu with karma: 5780 on 2011-09-06

This answer was ACCEPTED on the original site

Post score: 3


Original comments

Comment by hsu on 2011-09-06:
modified, both ends weighted down by mass :)

Comment by hsu on 2011-09-06:
@lu you're right, the last joint from link4 to the world creates a loop. removed.

Comment by David Lu on 2011-09-06:
I don't think this will work, since it breaks the fundamental tree structure of URDF.

Comment by David Lu on 2011-09-06:
s/slider/prismatic/

$\endgroup$
0
$\begingroup$

Rosanswers logo

There is no easy way to model this in URDF. The problem is that you only have one independent joint here, the one that connects the crank to the fixed frame. The rest of the angles (crank to lever, lever to block) are dependent on the first angle.

There are no set ways to control dependent joints. There are some nodes that support use of a mimic tag, although the mimic tag is not well documented. However, my understanding is that it only supports offsets and multipliers, not trigonometric functions, and thus may not work for you.

If you are only looking to visualize this mechanism, you can manually publish the joint angles yourself. However, if you want to simulate it in Gazebo or do any number of other operations, it can get a bit trickier.


Originally posted by David Lu with karma: 10932 on 2011-09-06

This answer was NOT ACCEPTED on the original site

Post score: 1

$\endgroup$
0
$\begingroup$

Rosanswers logo

I made a simple URDF crank for you.

<?xml version="1.0"?>
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
     xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
     xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
     xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" name="crank">

    <xacro:property name="R" value="1.0" />
    <xacro:property name="L" value="2.0" />
    <xacro:property name="x" value="0.1" />
    <xacro:property name="b" value="0.5" />
    <xacro:property name="pi" value="3.1415" />

  <link name="base_link">
    <visual>
      <geometry>
        <box size="0.05 .5 0.05"/>
      </geometry>
      <material name="green">
        <color rgba="0 1 0 1"/>
      </material>
    </visual>
  </link>

  <link name="crank_link">
    <visual>
      <geometry>
        <box size="${R} ${x} ${x}"/>
      </geometry>
      <origin xyz="${-R/2} 0 0" />

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

  <joint name="theta" type="continuous">
    <parent link="base_link"/>
    <child link="crank_link"/>
    <axis xyz="0 ${R} 0"/>
  </joint>


  <link name="lever_link">
    <visual>
      <geometry>
        <box size="${L} ${x} ${x}"/>
      </geometry>
      <origin xyz="${-L/2} 0 0"/>

      <material name="blue">
        <color rgba="0 0 .8 1"/>
      </material>
    </visual>
  </link>

  <joint name="alpha" type="continuous">
    <parent link="crank_link"/>
    <child link="lever_link"/>
    <origin xyz="${-R} 0 0"/>
    <axis xyz="0 1 0"/>
  </joint>

  <link name="box_link">
    <visual>
      <geometry>
        <box size="${b} ${b} ${b}"/>
      </geometry>
      <origin xyz="${-b/2} 0 0"/>
      <material name="red"/>
    </visual>
  </link>

  <joint name="psi" type="continuous">
    <parent link="lever_link"/>
    <child link="box_link"/>
    <origin xyz="${-L} 0 0"/>
    <axis xyz="0 1 0"/>
  </joint>

</robot>

#!/usr/bin/python

import roslib; roslib.load_manifest('crank')
import rospy
from sensor_msgs.msg import JointState
from math import pi, sin, asin
import math

R = 1.0
L = 2.0

if __name__ == '__main__':
    try:
        rospy.init_node('joint_state_publisher')
        pub = rospy.Publisher('joint_states', JointState)
        r = rospy.Rate(50) 
        theta = math.radians(45)

        # Publish Joint States
        while not rospy.is_shutdown():
            msg = JointState()
            msg.header.stamp = rospy.Time.now()
            msg.name = ['theta', 'alpha', 'psi']

            psi = asin( (R/L) * sin(theta) )
            alpha = - theta - psi

            msg.position = [theta, alpha, psi]
            print msg.position
            msg.velocity = [0]*3

            pub.publish(msg)

            theta += .1
            if theta >= 2 * pi:
                theta -= 2 * pi
            
            r.sleep()        
    except rospy.ROSInterruptException: pass

Originally posted by David Lu with karma: 10932 on 2011-09-06

This answer was NOT ACCEPTED on the original site

Post score: 4

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.