如何为 PlanarJoint 添加 JointActuator?
How to add JointActuator for PlanarJoint?
我正在研究一个简单的 2D 钉入孔示例,我想在其中直接控制 2D 中的钉(它只是一个盒子)。为此,我添加了一个平面关节以将钉子连接到世界,如操纵课程的示例中所示。
planar_joint_frame = plant.AddFrame(FixedOffsetFrame("planar_joint_frame", plant.world_frame(),RigidTransform(RotationMatrix.MakeXRotation(np.pi/2))))
peg_planar_joint_frame = plant.AddFrame(FixedOffsetFrame("peg_planar_joint_frame", peg.body_frame(),RigidTransform(RotationMatrix.MakeXRotation(np.pi/2), [0, 0, 0.025])))
peg_planar_joint = plant.AddJoint(PlanarJoint("peg_planar_joint", planar_joint_frame,peg_planar_joint_frame, damping=[0, 0, 0]))
然后我想给 peg_planar_joint
添加执行器,这样我就可以直接施加平面力 fx、fy 和扭矩 tau_z。
plant.AddJointActuator("peg_planar_joint", peg_planar_joint)
但是,我遇到了如下错误
SystemExit: Failure at bazel-out/k8-opt/bin/multibody/plant/_virtual_includes/multibody_plant_core/drake/multibody/plant/multibody_plant.h:1131 in AddJointActuator(): condition 'joint.num_velocities() == 1' failed.
看来JointActuator
只能加到PrismaticJoint
或RevoluteJoint
上,那是自由度为1的。所以我的问题是我可以将 JointActuator
分别添加到 PlanarJoint 的 x、y 和 RotZ 吗?如果不是,解决方法是什么?谢谢!
现在你必须自己添加棱柱和旋转关节来添加执行器。这是来自 https://github.com/RussTedrake/manipulation/blob/f868cd684a35ada15d6063c70daf1c9d61000941/force.ipynb
的片段
# Add a planar joint the old fashioned way (so that I can have three actuators):
gripper_false_body1 = plant.AddRigidBody(
"false_body1", gripper,
SpatialInertia(0, [0, 0, 0], UnitInertia(0, 0, 0)))
gripper_false_body2 = plant.AddRigidBody(
"false_body2", gripper,
SpatialInertia(0, [0, 0, 0], UnitInertia(0, 0, 0)))
gripper_x = plant.AddJoint(
PrismaticJoint("gripper_x", plant.world_frame(),
plant.GetFrameByName("false_body1"), [1, 0, 0], -.3, .3))
plant.AddJointActuator("gripper_x", gripper_x)
gripper_z = plant.AddJoint(
PrismaticJoint("gripper_z", plant.GetFrameByName("false_body1"),
plant.GetFrameByName("false_body2"), [0, 0, 1], 0.0,
0.5))
gripper_z.set_default_translation(0.3)
plant.AddJointActuator("gripper_z", gripper_z)
gripper_frame = plant.AddFrame(
FixedOffsetFrame(
"gripper_frame", plant.GetFrameByName("body", gripper),
RigidTransform(RotationMatrix.MakeXRotation(np.pi / 2))))
gripper_theta = plant.AddJoint(
RevoluteJoint("gripper_theta", plant.GetFrameByName("false_body2"),
gripper_frame, [0, -1, 0], -np.pi, np.pi))
plant.AddJointActuator("gripper_theta", gripper_theta)
这取决于你真正想要完成的事情。如果您只需要模拟具有外部作用力的 2D 系统,那么我建议您查看 MultibodyPlant::get_applied_generalized_force_input_port()
.
我正在研究一个简单的 2D 钉入孔示例,我想在其中直接控制 2D 中的钉(它只是一个盒子)。为此,我添加了一个平面关节以将钉子连接到世界,如操纵课程的示例中所示。
planar_joint_frame = plant.AddFrame(FixedOffsetFrame("planar_joint_frame", plant.world_frame(),RigidTransform(RotationMatrix.MakeXRotation(np.pi/2))))
peg_planar_joint_frame = plant.AddFrame(FixedOffsetFrame("peg_planar_joint_frame", peg.body_frame(),RigidTransform(RotationMatrix.MakeXRotation(np.pi/2), [0, 0, 0.025])))
peg_planar_joint = plant.AddJoint(PlanarJoint("peg_planar_joint", planar_joint_frame,peg_planar_joint_frame, damping=[0, 0, 0]))
然后我想给 peg_planar_joint
添加执行器,这样我就可以直接施加平面力 fx、fy 和扭矩 tau_z。
plant.AddJointActuator("peg_planar_joint", peg_planar_joint)
但是,我遇到了如下错误
SystemExit: Failure at bazel-out/k8-opt/bin/multibody/plant/_virtual_includes/multibody_plant_core/drake/multibody/plant/multibody_plant.h:1131 in AddJointActuator(): condition 'joint.num_velocities() == 1' failed.
看来JointActuator
只能加到PrismaticJoint
或RevoluteJoint
上,那是自由度为1的。所以我的问题是我可以将 JointActuator
分别添加到 PlanarJoint 的 x、y 和 RotZ 吗?如果不是,解决方法是什么?谢谢!
现在你必须自己添加棱柱和旋转关节来添加执行器。这是来自 https://github.com/RussTedrake/manipulation/blob/f868cd684a35ada15d6063c70daf1c9d61000941/force.ipynb
的片段 # Add a planar joint the old fashioned way (so that I can have three actuators):
gripper_false_body1 = plant.AddRigidBody(
"false_body1", gripper,
SpatialInertia(0, [0, 0, 0], UnitInertia(0, 0, 0)))
gripper_false_body2 = plant.AddRigidBody(
"false_body2", gripper,
SpatialInertia(0, [0, 0, 0], UnitInertia(0, 0, 0)))
gripper_x = plant.AddJoint(
PrismaticJoint("gripper_x", plant.world_frame(),
plant.GetFrameByName("false_body1"), [1, 0, 0], -.3, .3))
plant.AddJointActuator("gripper_x", gripper_x)
gripper_z = plant.AddJoint(
PrismaticJoint("gripper_z", plant.GetFrameByName("false_body1"),
plant.GetFrameByName("false_body2"), [0, 0, 1], 0.0,
0.5))
gripper_z.set_default_translation(0.3)
plant.AddJointActuator("gripper_z", gripper_z)
gripper_frame = plant.AddFrame(
FixedOffsetFrame(
"gripper_frame", plant.GetFrameByName("body", gripper),
RigidTransform(RotationMatrix.MakeXRotation(np.pi / 2))))
gripper_theta = plant.AddJoint(
RevoluteJoint("gripper_theta", plant.GetFrameByName("false_body2"),
gripper_frame, [0, -1, 0], -np.pi, np.pi))
plant.AddJointActuator("gripper_theta", gripper_theta)
这取决于你真正想要完成的事情。如果您只需要模拟具有外部作用力的 2D 系统,那么我建议您查看 MultibodyPlant::get_applied_generalized_force_input_port()
.