Skip to content

Commit

Permalink
v1.1.4 windows update
Browse files Browse the repository at this point in the history
  • Loading branch information
Jemin Hwangbo committed Aug 29, 2022
1 parent 08d4af4 commit e90e1c6
Show file tree
Hide file tree
Showing 194 changed files with 1,280 additions and 2,304 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.10)
set(RAISIM_VERSION 1.1.3)
set(RAISIM_VERSION 1.1.4)
project(raisim VERSION ${RAISIM_VERSION} LANGUAGES CXX)
set(CMAKE_MODULE_PATH "${PROJECT_SOURCE_DIR}/cmake" ${CMAKE_MODULE_PATH})

Expand Down
8 changes: 6 additions & 2 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ create_executable(laikago src/server/laikago.cpp)
create_executable(balls src/server/balls.cpp)
create_executable(atlas src/server/atlas.cpp)
create_executable(heightmap src/server/heightmap.cpp)
create_executable(robots src/server/aliengo.cpp)
create_executable(aliengo src/server/aliengo.cpp)
create_executable(materials src/server/material.cpp)
create_executable(materialStaticFriction src/server/materialStaticFriction.cpp)
create_executable(heightMapUsingPng src/server/heightMapUsingPng.cpp)
Expand All @@ -83,4 +83,8 @@ create_executable(xmlRader src/xml/xmlReader.cpp)
# mjcf files
create_executable(mjcf_humanoid src/mjcf/humanoid.cpp)
create_executable(mjcf_ant src/mjcf/ant.cpp)
create_executable(mjcf_cassie src/mjcf/cassie.cpp)
create_executable(mjcf_cassie src/mjcf/cassie.cpp)

# maps
create_executable(mountain1 src/maps/mountain1.cpp)
create_executable(office1 src/maps/office1.cpp)
1 change: 1 addition & 0 deletions examples/src/maps/README
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
This folder contains examples of supported maps by RaisimUnreal.
56 changes: 56 additions & 0 deletions examples/src/maps/mountain1.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// 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"
#if WIN32
#include <timeapi.h>
#endif

int main(int argc, char* argv[]) {
auto binaryPath = raisim::Path::setFromArgv(argv[0]);
raisim::World::setActivationKey(binaryPath.getDirectory() + "\\rsc\\activation.raisim");
#if WIN32
timeBeginPeriod(1); // for sleep_for function. windows default clock speed is 1/64 second. This sets it to 1ms.
#endif

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

/// create objects
auto heightmap = world.addHeightMap(binaryPath.getDirectory() + "\\rsc\\raisimUnrealMaps\\mountain1.png",
0, 0, 151.2, 151.2, 15.3/(39142-32640), -32640 * 15.3/(39142-32640));
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("mountain1");
server.focusOn(aliengo);
server.launchServer();

for (int i=0; i<2000000; i++) {
std::this_thread::sleep_for(std::chrono::microseconds(1000));
server.integrateWorldThreadSafe();
}

std::cout<<"mass "<<aliengo->getMassMatrix()[0]<<std::endl;

server.killServer();
}
58 changes: 58 additions & 0 deletions examples/src/maps/office1.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
// 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"
#if WIN32
#include <timeapi.h>
#endif

int main(int argc, char* argv[]) {
auto binaryPath = raisim::Path::setFromArgv(argv[0]);
raisim::World::setActivationKey(binaryPath.getDirectory() + "\\rsc\\activation.raisim");
#if WIN32
timeBeginPeriod(1); // for sleep_for function. windows default clock speed is 1/64 second. This sets it to 1ms.
#endif

/// create raisim world
raisim::World world(binaryPath.getDirectory() + "\\rsc\\raisimUnrealMaps\\office1.xml");
world.setTimeStep(0.001);


/// create objects
auto ground = world.addGround(0.02);
ground->setAppearance("hidden");
auto ball = world.addSphere(0.3, 2.0);
ball->setPosition(raisim::Vec<3>{0,0,2});
ball->setLinearVelocity(raisim::Vec<3>{1,1,0});

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("office1");
server.focusOn(aliengo);
server.launchServer();

for (int i=0; i<2000000; i++) {
std::this_thread::sleep_for(std::chrono::microseconds(20));
server.integrateWorldThreadSafe();
}

server.killServer();
}
3 changes: 2 additions & 1 deletion examples/src/server/anymals.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ int main(int argc, char* argv[]) {

/// create objects
auto ground = world.addGround(0, "gnd");
ground->setAppearance("wheat");
ground->setAppearance("hidden");
auto anymalB = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal\\urdf\\anymal.urdf");
auto anymalC = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal_c\\urdf\\anymal.urdf");

Expand Down Expand Up @@ -51,6 +51,7 @@ int main(int argc, char* argv[]) {

/// launch raisim server
raisim::RaisimServer server(&world);
server.setMap("wheat");
server.launchServer();
server.focusOn(anymalC);

Expand Down
3 changes: 2 additions & 1 deletion examples/src/server/atlas.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ int main(int argc, char* argv[]) {

/// create objects
auto ground = world.addGround();
ground->setAppearance("dune"); // this works only in raisimUnreal
ground->setAppearance("hidden"); // this works only in raisimUnreal

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

Expand All @@ -43,6 +43,7 @@ int main(int argc, char* argv[]) {

/// launch raisim server
raisim::RaisimServer server(&world);
server.setMap("dune");

/// use raisimUnreal to visualize the charts
auto timeSeries = server.addTimeSeriesGraph("body pos", {"atlas_x", "atlas_y", "atlas_z", "w", "x", "y", "z"}, "time", "pos");
Expand Down
1 change: 1 addition & 0 deletions examples/src/server/kinematicObject.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ int main(int argc, char* argv[]) {
auto movingGround = world.addBox(10, 10, 1, 10, "gnd");
movingGround->setBodyType(raisim::BodyType::KINEMATIC); // kinematic objects have infinite mass
movingGround->setPosition(0,0,-0.5);
movingGround->setAppearance("red");
auto anymalB = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal\\urdf\\anymal.urdf");

/// anymalC joint PD controller
Expand Down
1 change: 1 addition & 0 deletions examples/src/server/kinova.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ int main(int argc, char* argv[]) {

/// launch raisim server
raisim::RaisimServer server(&world);
server.setMap("simple");
server.launchServer();
server.focusOn(kinova);

Expand Down
11 changes: 8 additions & 3 deletions examples/src/server/primitives.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,9 @@ int main(int argc, char* argv[]) {
world.setTimeStep(0.002);

/// create objects
auto ground = world.addGround();

auto ground = world.addGround(-0.5);
ground->setName("ground");
ground->setAppearance("grid");
std::vector<raisim::Box*> cubes;
std::vector<raisim::Sphere*> spheres;
std::vector<raisim::Capsule*> capsules;
Expand All @@ -38,18 +39,22 @@ int main(int argc, char* argv[]) {
case 0:
cubes.push_back(world.addBox(1, 1, 1, 1));
ob = cubes.back();
ob->setAppearance("blue");
break;
case 1:
spheres.push_back(world.addSphere(0.5, 1));
ob = spheres.back();
ob->setAppearance("red");
break;
case 2:
capsules.push_back(world.addCapsule(0.5, 1., 1));
capsules.push_back(world.addCapsule(0.5, 0.5, 1));
ob = capsules.back();
ob->setAppearance("green");
break;
case 3:
cylinders.push_back(world.addCylinder(0.5, 0.5, 1));
ob = cylinders.back();
ob->setAppearance("0.5, 0.5, 0.8, 1.0");
break;
}
ob->setPosition(-N + 2. * i, -N + 2. * j, N * 2. + 2. * k);
Expand Down
3 changes: 3 additions & 0 deletions examples/src/server/rayDemo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,13 @@ int main(int argc, char* argv[]) {
terrainProperties.fractalGain = 0.25;

auto hm = world.addHeightMap(0.0, 0.0, terrainProperties);
hm->setAppearance("soil1");
auto cube = world.addBox(1,1,1,1);
cube->setPosition(3,0,3);
cube->setAppearance("blue");
auto cylinder = world.addCylinder(1, 1, 1);
cylinder->setPosition(3,3,3);
cylinder->setAppearance("yellow");
auto capsule = world.addCapsule(1, 1, 1);
capsule->setPosition(-3,3,3);
auto sphere = world.addSphere(1, 1);
Expand Down
5 changes: 2 additions & 3 deletions examples/src/server/rayDemo2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,9 @@ int main(int argc, char* argv[]) {
/// launch raisim server
raisim::RaisimServer server(&world);


/// this method should be called before server launch
auto scans = server.addInstancedVisuals("scan points",
raisim::InstancedVisuals::VisualBox,
raisim::Shape::Box,
{0.05, 0.05, 0.05},
{1,0,0,1},
{0,1,0,1});
Expand All @@ -63,7 +62,7 @@ int main(int argc, char* argv[]) {
Eigen::Vector3d direction;

for(int time=0; time<1000000; time++) {
raisim::MSLEEP(1.0);
raisim::MSLEEP(1);
server.integrateWorldThreadSafe();
raisim::Vec<3> lidarPos; raisim::Mat<3,3> lidarOri;
robot->getFramePosition("imu_joint", lidarPos);
Expand Down
14 changes: 8 additions & 6 deletions examples/src/server/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,18 +41,20 @@ int main(int argc, char **argv) {
anymal->setGeneralizedForce(Eigen::VectorXd::Zero(anymal->getDOF()));
anymal->setName("Anymal");

auto depthSensor = anymal->getSensor<raisim::DepthCamera>("depth_camera_front_camera_parent:depth");
depthSensor->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
auto depthSensor1 = anymal->getSensor<raisim::DepthCamera>("depth_camera_front_camera_parent:depth");
depthSensor1->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
auto rgbCamera1 = anymal->getSensor<raisim::RGBCamera>("depth_camera_front_camera_parent:color");
rgbCamera1->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);

auto rgbCamera = anymal->getSensor<raisim::RGBCamera>("depth_camera_front_camera_parent:color");
rgbCamera->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
auto depthSensor2 = anymal->getSensor<raisim::DepthCamera>("depth_camera_rear_camera_parent:depth");
depthSensor2->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
auto rgbCamera2 = anymal->getSensor<raisim::RGBCamera>("depth_camera_rear_camera_parent:color");
rgbCamera2->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);

server.launchServer();
for (int k = 0; k < loopN; k++) {
world.integrate();
raisim::MSLEEP(world.getTimeStep() * 1000);
//std::cout<<"first b pixel rgb "<<int(rgbCamera->getImageBuffer()[0])<<std::endl; // bgra format
//std::cout<<"first depth pixel "<<depthSensor->getDepthArray()[0]<<std::endl;
}

server.killServer();
Expand Down
2 changes: 1 addition & 1 deletion examples/src/server/visualObjects.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ int main(int argc, char* argv[]) {
auto visSphere = server.addVisualSphere("v_sphere", 1.0, 1, 1, 1, 1);
auto visBox = server.addVisualBox("v_box", 1, 1, 1, 1, 1, 1, 1);
auto visCylinder = server.addVisualCylinder("v_cylinder", 1, 1, 0, 1, 0, 1);
auto visCapsule = server.addVisualCapsule("Cylinder", 1, 0.5, 0, 0, 1, 1);
auto visCapsule = server.addVisualCapsule("v_capsule", 1, 0.5, 0, 0, 1, 1);
auto mesh = world.addMesh(binaryPath.getDirectory() + "/rsc/monkey/monkey.obj", 1, inertia, com);
auto visMesh = server.addVisualMesh("v_mesh", binaryPath.getDirectory() + "/rsc/monkey/monkey.obj");
auto anymalB = server.addVisualArticulatedSystem("v_anymal", binaryPath.getDirectory() + "/rsc/anymal/urdf/anymal.urdf");
Expand Down
Binary file removed raisim/win32/mt_debug/bin/anymal_stress_test.exe
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/anymal_stress_test.pdb
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/atlas.exe
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/atlas.ilk
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/atlas.pdb
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/balls.pdb
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/cartPole.exe
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/cartPole.ilk
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/cartPole.pdb
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/compound.exe
Binary file not shown.
Binary file removed raisim/win32/mt_debug/bin/compound.pdb
Binary file not shown.
Loading

0 comments on commit e90e1c6

Please sign in to comment.