void declareArticulatedObjectWrapper()

in src/esp/bindings/PhysicsObjectBindings.cpp [333:538]


void declareArticulatedObjectWrapper(py::module& m,
                                     const std::string& objType,
                                     const std::string& classStrPrefix) {
  // ==== ManagedArticulatedObject ====
  py::class_<ManagedArticulatedObject,
             AbstractManagedPhysicsObject<ArticulatedObject>,
             std::shared_ptr<ManagedArticulatedObject>>(m,
                                                        classStrPrefix.c_str())
      .def_property_readonly(
          "global_scale", &ManagedArticulatedObject::getGlobalScale,
          R"(The uniform global scaling applied to this object during import.)")
      .def("get_link_scene_node", &ManagedArticulatedObject::getLinkSceneNode,
           ("Get the scene node for this " + objType +
            "'s articulated link specified by the passed "
            "link_id. Use link_id==-1 to get the base link.")
               .c_str(),
           "link_id"_a)
      .def("get_link_visual_nodes",
           &ManagedArticulatedObject::getLinkVisualSceneNodes,
           ("Get a list of the visual scene nodes from this " + objType +
            "'s articulated link specified by the passed "
            "link_id. Use link_id==-1 to get the base link.")
               .c_str(),
           "link_id"_a)
      .def("get_link", &ManagedArticulatedObject::getLink,
           ("Get this " + objType +
            "'s articulated link specified by the passed "
            "link_id. Use link_id==-1 to get the base link.")
               .c_str(),
           "link_id"_a)
      .def(
          "get_link_ids", &ManagedArticulatedObject::getLinkIds,
          ("Get a list of this " + objType + "'s individual link ids.").c_str())
      .def_property_readonly("link_object_ids",
                             &ManagedArticulatedObject::getLinkObjectIds,
                             ("Get a dict mapping Habitat object ids to this " +
                              objType + "'s link ids.")
                                 .c_str())
      .def_property_readonly(
          "num_links", &ManagedArticulatedObject::getNumLinks,
          ("Get the number of links this " + objType + " holds.").c_str())
      .def_property(
          "root_linear_velocity",
          &ManagedArticulatedObject::getRootLinearVelocity,
          &ManagedArticulatedObject::setRootLinearVelocity,
          ("The linear velocity of the " + objType + "'s root.").c_str())
      .def_property(
          "root_angular_velocity",
          &ManagedArticulatedObject::getRootAngularVelocity,
          &ManagedArticulatedObject::setRootAngularVelocity,
          ("The angular velocity (omega) of the " + objType + "'s root.")
              .c_str())
      .def_property("joint_forces", &ManagedArticulatedObject::getJointForces,
                    &ManagedArticulatedObject::setJointForces,
                    ("Get or set the joint forces/torques (indexed by DoF id) "
                     "currently acting on this " +
                     objType + ".")
                        .c_str())
      .def("add_joint_forces", &ManagedArticulatedObject::addJointForces,
           ("Add joint forces/torques (indexed by DoF id) to this " + objType +
            ".")
               .c_str(),
           "forces"_a)
      .def_property("joint_velocities",
                    &ManagedArticulatedObject::getJointVelocities,
                    &ManagedArticulatedObject::setJointVelocities,
                    ("Get or set this " + objType +
                     "'s joint velocities, indexed by DOF id.")
                        .c_str())
      .def_property("joint_positions",
                    &ManagedArticulatedObject::getJointPositions,
                    &ManagedArticulatedObject::setJointPositions,
                    ("Get or set this " + objType +
                     "'s joint positions. For link to index mapping see "
                     "get_link_joint_pos_offset and get_link_num_joint_pos.")
                        .c_str())
      .def_property_readonly("joint_position_limits",
                             &ManagedArticulatedObject::getJointPositionLimits,
                             ("Get a tuple of lists of this " + objType +
                              "'s joint limits (lower, upper).")
                                 .c_str())
      .def("get_link_dof_offset", &ManagedArticulatedObject::getLinkDoFOffset,
           ("Get the index of this " + objType +
            "'s link's first DoF in the global DoF array. Link specified by "
            "the given link_id.")
               .c_str(),
           "link_id"_a)
      .def("get_link_num_dofs", &ManagedArticulatedObject::getLinkNumDoFs,
           ("Get the number of DoFs for the parent joint of this " + objType +
            "'s link specified by the given link_id.")
               .c_str(),
           "link_id"_a)
      .def("get_link_joint_pos_offset",
           &ManagedArticulatedObject::getLinkJointPosOffset,
           ("Get the index of this " + objType +
            "'s link's first position in the global joint positions array. "
            "Link specified by the given link_id.")
               .c_str(),
           "link_id"_a)
      .def("get_link_num_joint_pos",
           &ManagedArticulatedObject::getLinkNumJointPos,
           ("Get the number of position variables for the parent joint of "
            "this " +
            objType + "'s link specified by the given link_id.")
               .c_str(),
           "link_id"_a)
      .def("get_link_joint_type", &ManagedArticulatedObject::getLinkJointType,
           ("Get the type of the parent joint for this " + objType +
            "'s link specified by the given link_id.")
               .c_str(),
           "link_id"_a)
      .def("get_link_joint_name", &ManagedArticulatedObject::getLinkJointName,
           ("Get the name of the parent joint for this " + objType +
            "'s link specified by the given link_id.")
               .c_str(),
           "link_id"_a)
      .def("get_link_name", &ManagedArticulatedObject::getLinkName,
           ("Get the name of the this " + objType +
            "'s link specified by the given link_id.")
               .c_str(),
           "link_id"_a)
      .def("add_link_force", &ManagedArticulatedObject::addArticulatedLinkForce,
           ("Apply the given force to this " + objType +
            "'s link specified by the given link_id")
               .c_str(),
           "link_id"_a, "force"_a)
      .def("get_link_friction",
           &ManagedArticulatedObject::getArticulatedLinkFriction,
           ("Get the link friction from this " + objType +
            "'s link specified by the provided link_id")
               .c_str(),
           "link_id"_a)
      .def("set_link_friction",
           &ManagedArticulatedObject::setArticulatedLinkFriction,
           ("Set the link friction for this " + objType +
            "'s link specified by the provided link_id to the provided "
            "friction value.")
               .c_str(),
           "link_id"_a, "friction"_a)
      .def("clear_joint_states", &ManagedArticulatedObject::reset,
           ("Clear this " + objType +
            "'s joint state by zeroing forces, torques, positions and "
            "velocities. Does not change root state.")
               .c_str())
      .def_property_readonly(
          "can_sleep", &ManagedArticulatedObject::getCanSleep,
          ("Whether or not this " + objType + " can be put to sleep").c_str())
      .def_property(
          "auto_clamp_joint_limits",
          &ManagedArticulatedObject::getAutoClampJointLimits,
          &ManagedArticulatedObject::setAutoClampJointLimits,
          ("Get or set whether this " + objType +
           "'s joints should be autoclamped to specified joint limits.")
              .c_str())
      .def("clamp_joint_limits", &ManagedArticulatedObject::clampJointLimits,
           ("Clamp this " + objType +
            "'s current pose to specified joint limits.")
               .c_str())
      // Joint Motor API
      .def_property_readonly(
          "existing_joint_motor_ids",
          &ManagedArticulatedObject::getExistingJointMotors,
          ("A dictionary mapping all of this " + objType +
           "'s joint motor ids to their respective links/joints.")
              .c_str())
      .def("create_all_motors",
           &ManagedArticulatedObject::createMotorsForAllDofs,
           ("Make motors for all of this " + objType +
            "'s links which support motors (Revolute, Prismatic, Spherical).")
               .c_str(),
           "settings"_a)
      .def("update_all_motor_targets",
           &ManagedArticulatedObject::updateAllMotorTargets,
           ("Update all motors targets for this " + objType +
            "'s joints which support motors (Revolute, Prismatic, Spherical) "
            "from a state array. By default, state is interpreted as position "
            "targets unless `velocities` is specified. Expected input is the "
            "full length position or velocity array for this object. This "
            "function will safely skip states for joints which don't support "
            "JointMotors.")
               .c_str(),
           "state_targets"_a, "velocities"_a = false)
      .def("create_joint_motor", &ManagedArticulatedObject::createJointMotor,
           ("Create a joint motor for the specified DOF on this " + objType +
            " using the provided JointMotorSettings")
               .c_str(),
           "link"_a, "settings"_a)
      .def(
          "remove_joint_motor", &ManagedArticulatedObject::removeJointMotor,
          ("Remove the joint motor specified by the given motor_id from this " +
           objType + ".")
              .c_str(),
          "motor_id"_a)
      .def("get_joint_motor_settings",
           &ManagedArticulatedObject::getJointMotorSettings,
           ("Get the JointMotorSettings for the motor with the given "
            "motor_id in this " +
            objType + ".")
               .c_str(),
           "motor_id"_a)
      .def("update_joint_motor", &ManagedArticulatedObject::updateJointMotor,
           ("Update the JointMotorSettings for the motor on this " + objType +
            " specified by the provided motor_id.")
               .c_str(),
           "motor_id"_a, "settings"_a);
}  // declareArticulatedObjectWrapper