I would like to create an object in pydrake that is loaded from a URDF (e.g. just a single-link URDF that has an object mesh), and be able to manually set the pose of the object as I wish after creation. What I've been doing so far is this:
urdf = FindResourceOrThrow(my_urdf_path)
parser.AddModelFromFile(urdf)
frame = plant.GetFrameByName("my_frame")
T = RigidTransform(p=pos, rpy=RollPitchYaw(rpy))
plant.WeldFrames(plant.world_frame(), frame, T)
That lets me set the pose on creation. However, I don't know how to change the pose once the plant has been finalized. I assume there's a way to do this but am struggling to find an example. Thanks in advance for your help.
I believe you can do it as follows: (1) Attach a FixedOffsetFrame (e.g., "robot_base") to the world. The offset is a parameter of the context, not State dofs. (2) Weld the robot to robot_base. (3) Re-pose that frame in a Context.
(1) goes like:
robot_base = plant.AddFrame(frame=FixedOffsetFrame(
name="robot_base",
P=plant.world_frame(),
X_PF=RigidTransform_[float].Identity(),
model_instance=None))
(3) goes like:
robot_base.SetPoseInBodyFrame(context=context, X_PF=new_pose)
(Yes, Drake's examples should show this better; it's a bit obscure right now.)