Jianlan Posted June 18, 2018 Share Posted June 18, 2018 Hello, We have a Sawyer robot with Intera 5.2, and a Robotiq 3 finger gripper installed on it (https://robotiq.com/products/3-finger-adaptive-robot-gripper), it is 2.5 kg. We entered the payload information in Intera Studio, it looked fine in Intera mode. However, it did not work in SDK mode, the robot can't even hold it self, and motors started backdriving, can't move even. The specified payload of Sawyer is 4KG, the gripper plus coupling is surely under this, We wonder how to properly enter payload information or how to actually solve it in SDK mode. Thank you. 1 Quote Link to comment Share on other sites More sharing options...
Ian McMahon Posted June 18, 2018 Share Posted June 18, 2018 Hi Jianlan, There are two ways to enter payload in SDK mode for Sawyer, one is supplying Sawyer with the relevant URDF fragment, or by using the Clicksmart Gripper mounting plate, with stored end effector data built into its memory. If you're using the Clicksmart, then configuring via Intera is the way to go. It will retain its configuration when booted into SDK mode, and maintain this information between reboots. Based on your description, it seems you're not using the Clicksmart plate. In that case, you will supply the robot with the relevant URDF data from your computer using the send_urdf_fragment script. That fragment can either be a full actuated gripper URDF or a simple fixed joint with payload, so long as it is attached to the "right_hand" link. For instance: Filename: basic_robotiq_gripper.xacro <?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="basic_robotiq_gripper"> <xacro:macro name="basic_robotiq_gripper" params="side"> <joint name="${side}_gripper_base" type="fixed"> <origin rpy="0 0 0" xyz="0 0 0"/> <!-- Enter the 3D pose of your end effector frame here w.r.t. end of arm --> <parent link="${side}_hand"/> <child link="${side}_robotiq_gripper"/> </joint> <link name="${side}_robotiq_gripper"> <inertial> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <!-- only modify this if there is an C.O.M. offset w.r.t your gripper_base joint above --> <mass value="2.5"/> <!-- Enter your mass and inertial properties here --> <inertia ixx="1e-08" ixy="0" ixz="0" iyy="1e-08" iyz="0" izz="1e-08"/> </inertial> </link> </xacro:macro> <xacro:basic_robotiq_gripper side="right"/> </robot> then in a terminal, supply the link onboard the robot to attach this object (right_hand here), the joint from your URDF (right_gripper_base from above), and the location of the file containing all of your URDF details (basic_robotiq_gripper.xacro in this example): $ rosrun intera_interface send_urdf_fragment.py --link right_hand --joint right_gripper_base --file basic_robotiq_gripper.xacro One thing to note, this needs to be run anytime you've rebooted the Sawyer, as the configuration is not saved inside of a Clicksmart toolplate. Please let us know if you have any additional questions on this. Hope this helps! ~ Ian 1 Quote Link to comment Share on other sites More sharing options...
Jianlan Posted June 19, 2018 Author Share Posted June 19, 2018 (edited) Hi Ian, Thank you so much, it worked somehow. Just to double-confirm, we enter every unit in the xml in meter and kg, is this what it's supposed to be ? thank you Jianlan Edited June 19, 2018 by Jianlan Quote Link to comment Share on other sites More sharing options...
Ian McMahon Posted June 20, 2018 Share Posted June 20, 2018 Hi Jianlan, Yes, all units are in S.I. (per ROS standards), with Kilograms and Meters. Cheers, ~ Ian 1 Quote Link to comment Share on other sites More sharing options...
Jianlan Posted June 20, 2018 Author Share Posted June 20, 2018 Hi Ian, Thank you for the confirmation. For the convenience of other people, if you are using a Robotiq 3-finger gripper with correct coupling elements, attached file is our calculation of Inertia, COM etc. it works well in our case <?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="basic_robotiq_gripper"> <xacro:macro name="basic_robotiq_gripper" params="side"> <joint name="${side}_gripper_base" type="fixed"> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <!-- Enter the 3D pose of your end effector frame here w.r.t. end of arm --> <parent link="${side}_hand"/> <child link="${side}_robotiq_gripper"/> </joint> <link name="${side}_robotiq_gripper"> <inertial> <origin rpy="0 0 0" xyz="-8.0e-3 0.0 60.0e-3"/> <!-- only modify this if there is an C.O.M. offset w.r.t your gripper_base joint above --> <mass value="2.6"/> <!-- Enter your mass and inertial properties here --> <inertia ixx="7424e-6" ixy="0" ixz="-650e-6" iyy="8924e-6" iyz="0" izz="7243e-6"/> </inertial> </link> </xacro:macro> <xacro:basic_robotiq_gripper side="right"/> </robot> Jianlan 2 Quote Link to comment Share on other sites More sharing options...
Recommended Posts
Join the conversation
You can post now and register later. If you have an account, sign in now to post with your account.