4.5.0
4.2.0
4.1.0
4.0.0
4.5.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: RTX 4090
Topic Description
Unable to change the robot orientation for inverse kinematics
Detailed Description
I followed the Adding a new manipulator tutorial to add my xarm6 robot. Everything worked just fine, I want to now mount the robot to ceiling, so I am making the following changes in both the FollowTarget task and also in my main script, however, the robot behaves wierdly as shown below
Do I have to make changes to the kinematics solver class? Keep in mind that I am using the same urdf and usd file I got from following that tutorial, I just imported it in another scene.
Should I consider using a different kinematic solver?
Additional Context
Everything is EXACTLY as in the tutorial, I am just loading this scene using omni.usd and getting the robot prims from this usd file. I am using a visual cuboid for the target.
@adnanamir010 , mounting the robot on the ceiling probably changes physics as well (parameters which might be needed for the joints regarding damping and stiffness). On mounting it to the ceiling, does the robot behave as expected without any planning/moving task? that might be the first sanity check needed
The robot’s base link relative to world is correct. It is [0,0,1] and the orientation is [0,1,0,0]. After some deep dive into the documentation and the source code, LulaKinematicsSolver actually requires you to explicitly update the robot’s pose which is not done in the tutorial.
I managed to fix this by making the following changes to my code
class KinematicsSolver(ArticulationKinematicsSolver):
def __init__(self, robot_articulation: Articulation, end_effector_frame_name: Optional[str] = None) -> None:
"""
Initialize the kinematics solver with the robot's articulation and configuration files.
Args:
robot_articulation: The robot articulation object
end_effector_frame_name: Name of the end effector frame (defaults to "link_eef" for xarm6)
"""
self._kinematics = LulaKinematicsSolver(
robot_description_path="LULA_PATH",
urdf_path="URDF_PATH"
)
if end_effector_frame_name is None:
end_effector_frame_name = "link_eef"
ArticulationKinematicsSolver.__init__(self, robot_articulation, self._kinematics, end_effector_frame_name)
self._robot_articulation = robot_articulation
self.update_base_pose()
def update_base_pose(self) -> None:
"""
Update the robot's base pose in the kinematics solver.
This should be called whenever the robot's base position or orientation changes.
"""
base_position, base_orientation = self._robot_articulation.get_world_pose()
# Update the kinematics solver with the robot's base pose
self._kinematics.set_robot_base_pose(base_position, base_orientation)
def compute_inverse_kinematics(
self,
target_position: np.ndarray,
target_orientation: np.ndarray,
update_base_pose: bool = True
) -> Tuple[np.ndarray, bool]:
"""
Compute inverse kinematics with automatic base pose update.
Args:
target_position: Target position for the end effector in world coordinates
target_orientation: Target orientation for the end effector (quaternion)
update_base_pose: Whether to update the base pose before computing IK
Returns:
Tuple containing joint positions and success flag
"""
# Update the base pose if requested
if update_base_pose:
self.update_base_pose()
return super().compute_inverse_kinematics(target_position, target_orientation)
Now the robot updates the base pose upon initialization (This is the case with a pre defined scene) and there is an option to continue updating the base pose for something like a manipulator mounted on a mobile base.