Server Example: Procedural Heightmap

Overview

Creates a procedural heightmap and places ANYmal on top. Use this to see how to configure fractal terrain properties and run a robot on generated terrain.

Screenshot

../../../_images/heightMapUsingTerrainGenerator.gif

Binary

CMake target and executable name: procedural_heightmap.

Run

Build and run from your build directory:

cmake --build . --target procedural_heightmap
./procedural_heightmap

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

Details

  • Generates terrain from TerrainProperties (fractal noise).

  • Spawns ANYmal on the heightmap with PD control.

  • Demonstrates procedural heightmap creation and appearance.

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]);

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

  /// create objects
  raisim::TerrainProperties terrainProperties;
  terrainProperties.frequency = 0.2;
  terrainProperties.zScale = 3.0;
  terrainProperties.xSize = 20.0;
  terrainProperties.ySize = 20.0;
  terrainProperties.xSamples = 50;
  terrainProperties.ySamples = 50;
  terrainProperties.fractalOctaves = 3;
  terrainProperties.fractalLacunarity = 2.0;
  terrainProperties.fractalGain = 0.25;
  terrainProperties.heightOffset = -1;
  raisim::HeightMap* hm = world.addHeightMap(0.0, 0.0, terrainProperties);
  hm->setAppearance("red");

  std::vector<raisim::ArticulatedSystem*> anymals;

  /// ANYmal joint PD controller
  Eigen::VectorXd jointNominalConfig(19), jointVelocityTarget(18);
  Eigen::VectorXd jointState(18), jointForce(18), jointPgain(18),
      jointDgain(18);
  jointPgain.setZero();
  jointDgain.setZero();
  jointVelocityTarget.setZero();
  jointPgain.tail(12).setConstant(200.0);
  jointDgain.tail(12).setConstant(10.0);

  constexpr size_t N = 6;

  for (size_t i = 0; i < N; i++) {
    for (size_t j = 0; j < N; j++) {
      anymals.push_back(world.addArticulatedSystem(
          binaryPath.getDirectory() + "\\rsc\\anymal\\urdf\\anymal.urdf"));
      anymals.back()->setGeneralizedCoordinate(
          {double(2 * i)-1, double(j), 2.5, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8,
           -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8});
      anymals.back()->setGeneralizedForce(
          Eigen::VectorXd::Zero(anymals.back()->getDOF()));
      anymals.back()->setControlMode(
          raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE);
      anymals.back()->setPdGains(jointPgain, jointDgain);
      anymals.back()->setName("anymal" + std::to_string(j + i * N));
    }
  }

  /// launch raisim server
  raisim::RaisimServer server(&world);
  server.launchServer();


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

  server.killServer();
}