Map Example: Lake1 Heightmap
Overview
Uses the lake1 heightmap image and spawns Aliengo to walk on the terrain. This example shows how to configure heightmap scaling and map selection for a large outdoor scene.
Screenshot
Binary
CMake target and executable name: map_lake1_heightmap.
Run
Build and run from your build directory:
cmake --build . --target map_lake1_heightmap
./map_lake1_heightmap
On Windows, run map_lake1_heightmap.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 lake1 heightmap PNG with scale/offset.
Spawns Aliengo with PD posture control at a low start height.
Sets the Unreal map to
lake1and focuses on the robot.
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 "raisim_unreal_map_hint.hpp"
int main(int argc, char* argv[]) {
auto binaryPath = raisim::Path::setFromArgv(argv[0]);
raisim::World::setActivationKey(binaryPath.getDirectory() + "\\rsc\\activation.raisim");
raisim_examples::printRaisimUnrealMapHint("lake1");
/// create raisim world
raisim::World world;
world.setTimeStep(0.001);
/// create objects
auto heightmap = world.addHeightMap(binaryPath.getDirectory() + "\\rsc\\raisimUnrealMaps\\lake1.png",
0, 0, 504, 504, 38.0/(37312-32482), -32515 * 38.0/(37312-32482));
heightmap->setAppearance("hidden");
auto aliengo = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\aliengo\\aliengo.urdf");
/// aliengo joint PD controller
Eigen::VectorXd jointNominalConfig(aliengo->getGeneralizedCoordinateDim()), jointVelocityTarget(aliengo->getDOF());
jointNominalConfig << 0, 0, 1.24, 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;
jointVelocityTarget.setZero();
Eigen::VectorXd jointPgain(aliengo->getDOF()), jointDgain(aliengo->getDOF());
jointPgain.tail(12).setConstant(100.0);
jointDgain.tail(12).setConstant(1.0);
aliengo->setGeneralizedCoordinate(jointNominalConfig);
aliengo->setGeneralizedForce(Eigen::VectorXd::Zero(aliengo->getDOF()));
aliengo->setPdGains(jointPgain, jointDgain);
aliengo->setPdTarget(jointNominalConfig, jointVelocityTarget);
aliengo->setName("aliengo");
/// launch raisim server
raisim::RaisimServer server(&world);
server.setMap("lake1");
server.focusOn(aliengo);
server.launchServer();
for (int i=0; i<2000000; i++) {
RS_TIMED_LOOP(int(world.getTimeStep()*1e6))
server.integrateWorldThreadSafe();
}
std::cout<<"mass "<<aliengo->getMassMatrix()[0]<<std::endl;
server.killServer();
}