Please provide all relevant details below before submitting your post. This will help the community provide more accurate and timely assistance. After submitting, you can check the appropriate boxes. Remember, you can always edit your post later to include additional information if needed.
Isaac Sim Version
4.2.0
4.1.0
4.0.0
2023.1.1
2023.1.0-hotfix.1
Other (please specify):
Operating System
Ubuntu 22.04
Ubuntu 20.04
Windows 11
Windows 10
Other (please specify):
GPU Information
Model: NVIDIA GeForce RTX 2080
Driver Version: 535.183.01
Topic Description
Detailed Description
I am building a basic demo with the pick and place controller. I have a UR10 robotic arm and the object to pick up is a DynamicCuboid. To perform the task, i am using the PickPlaceController from the universal_robots.controllers package and I based my code on the pickplace task.
However, i have a weird error while placing the object to pick on a table. See the videos below.
1st video without table: as expected, the object falls on the floor and the robot pick it.
2nd video with table: the object falls on the table but the robot tries to reach the position in which the object would be without the table. The robot is thus colliding with the table.
Weirdly, the position of the cube as retrieved by the controller is the right one when i compare it with the GUI.
My workflow is “Extension” and I chose to use a Loaded Scenario Template from the documentation.
i am using this object_pos, _ = self._object.get_world_pose() where self._object is the DynamicCuboid I added to the scene.
I also tried to use local coordinates with the appropriate transforms (so that the object is express in the robot’s coordinate system) but the behavior is also the same).
I looks like there is a discrepancy between the physics engine and the stage
Hey,
Just to let you know that i found my issue.
It comes from the manipulators_controllers.PickPlaceController which does not consider the Z-position of the object to pick&place…
So I had to slightly modify this controller and it is now working as expected!
For anyone interested here i had to change the method _get_target_hs() by passing it the picking-z-position and change how the return h parameter is calculated.
i am using the following function where picking_z is picking_position[2]and placing_z is placing_position[2]. You should take care to include these values in the call of the function
def _get_target_hs(self, picking_z, placing_z):
if self._event == 0:
h = picking_z + self._h1
elif self._event == 1:
a = self._mix_sin(max(0, self._t))
h = self._combine_convex(picking_z + self._h1, self._h0, a)
elif self._event == 3:
h = self._h0
elif self._event == 4:
a = self._mix_sin(max(0, self._t))
h = self._combine_convex(self._h0, placing_z + self._h1, a)
elif self._event == 5:
h = placing_z + self._h1
elif self._event == 6:
h = self._combine_convex(placing_z + self._h1, placing_z, self._mix_sin(self._t))
elif self._event == 7:
h = placing_z
elif self._event == 8:
h = self._combine_convex(placing_z, placing_z + self._h1, self._mix_sin(self._t))
elif self._event == 9:
h = picking_z + self._h1
else:
raise ValueError()
return h
``
Can you help me with what is the intuition behind this, as you are right when we pick an object from ground the manipulator pick it up easily but in case where we pick from different base it colliding in the object can you help what will this function will exactly do !