Server Example: Minitaur PD

Overview

Runs Minitaur with PD control, including per-joint gains that zero out unactuated joints. It is a compact reference for legged robot PD setup.

Screenshot

../../../_images/minitaur_cpp.png

Binary

CMake target and executable name: minitaur_pd.

Run

Build and run from your build directory:

cmake --build . --target minitaur_pd
./minitaur_pd

On Windows, run minitaur_pd.exe instead. This example uses RaisimServer. Start a visualizer client (RaisimUnity, RaisimUnreal, or the rayrai TCP viewer) and connect to port 8080.

Details

  • Loads the Minitaur URDF (closed-loop) and applies PD to actuated joints.

  • Sets gains to zero for unactuated joints in the closed-loop model.

  • Focuses the camera on the robot to show posture stability.

Source

// This file is part of RaiSim. You must obtain a valid license from RaiSim Tech
// Inc. prior to usage.

#include "raisim/RaisimServer.hpp"
#include "raisim/World.hpp"
#include "rayrai_tcp_viewer_hint.hpp"

int main(int argc, char* argv[]) {
  auto binaryPath = raisim::Path::setFromArgv(argv[0]);
  const std::string rscPath = (binaryPath.getDirectory() + "/../../rsc").getString();
  raisim::World::setActivationKey(rscPath + "/activation.raisim");

  raisim::RaiSimMsg::setFatalCallback([](){throw;});

  /// create raisim world
  raisim::World world;
  world.setTimeStep(0.001);

  /// create objects
  world.addGround();
  auto minitaur = world.addArticulatedSystem(rscPath + "/minitaur/minitaur.urdf");
  minitaur->setName("minitaur");

/// anymalC joint PD controller
  Eigen::VectorXd jointNominalConfig(minitaur->getGeneralizedCoordinateDim()), jointVelocityTarget(minitaur->getDOF());
  jointNominalConfig << 0,0,0.35, 0,0,1,0,
      -M_PI_2,-2.2,-M_PI_2,-2.2,
      -M_PI_2,-2.2,-M_PI_2,-2.2,
      -M_PI_2,-2.2,-M_PI_2,-2.2,
      -M_PI_2,-2.2,-M_PI_2,-2.2;
  jointVelocityTarget.setZero();

  Eigen::VectorXd jointPgain(minitaur->getDOF()), jointDgain(minitaur->getDOF());
  /// we set the gains of the unactuated joints to zero
  jointPgain << 0,0,0, 0,0,0,
      20,0.,20,0.,
      20,0.,20,0.,
      20,0.,20,0.,
      20,0.,20,0.;
  jointDgain << 0,0,0, 0,0,0,
      0.1,0.,0.1,0.,
      0.1,0.,0.1,0.,
      0.1,0.,0.1,0.,
      0.1,0.,0.1,0.;

  minitaur->setGeneralizedCoordinate(jointNominalConfig);
  minitaur->setGeneralizedForce(Eigen::VectorXd::Zero(minitaur->getDOF()));
  minitaur->setPdGains(jointPgain, jointDgain);
  minitaur->setPdTarget(jointNominalConfig, jointVelocityTarget);
  minitaur->setName("minitaur");

  /// launch raisim server
  raisim::RaisimServer server(&world);
  server.launchServer();
  raisim_examples::warnIfNoClientConnected(server);
  server.focusOn(minitaur);

  for (int i=0; i<2000000; i++) {
    RS_TIMED_LOOP(1e6*world.getTimeStep())
    server.integrateWorldThreadSafe();
  }

  server.killServer();
}