Hello, I was running into an error when loading in Mujoco xml file for Agility Robotics' Digit. I tried loading in both Raisim and RaisimGym and both loaded in the terminal but provided the same error in the visualizer. However, I think the model was able to train in RaisimGym but only having troubles in the visualizer. I have tested my laptop and it was able to train the anymal example with the visualizer and load in urdf files. Please let me know what you think.
Thank you in advance!
##############Error Message######################
##############Code for Raisim######################
// This file is part of RaiSim. You must obtain a valid license from RaiSim Tech
// Inc. prior to usage.
include "raisim/World.hpp"
include "raisim/RaisimServer.hpp"
if WIN32
include
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.
The issue is that our mjcf reader is not exactly the same as the MuJoCo one. I will try to improve the reader in the next push. I recommend converting the file to URDF. There must be a converter available online
Hello, I was running into an error when loading in Mujoco xml file for Agility Robotics' Digit. I tried loading in both Raisim and RaisimGym and both loaded in the terminal but provided the same error in the visualizer. However, I think the model was able to train in RaisimGym but only having troubles in the visualizer. I have tested my laptop and it was able to train the anymal example with the visualizer and load in urdf files. Please let me know what you think. Thank you in advance!
##############Error Message######################
##############Code for Raisim###################### // This file is part of RaiSim. You must obtain a valid license from RaiSim Tech // Inc. prior to usage.
include "raisim/World.hpp"
include "raisim/RaisimServer.hpp"
if WIN32
include
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
raisim::World world(binaryPath.getDirectory()+"\..\..\rsc\digit\digit-v3.xml"); raisim::RaisimServer server(&world); auto digit = static_cast<raisim::ArticulatedSystem*>(world.getObject("base")); std::vector name=digit->getMovableJointNames();
std::cout<<"Movable Joints: "<<name[36]<<" "<<name[24]<<std::endl;
Eigen::VectorXd jointNominalConfig(digit->getGeneralizedCoordinateDim()), jointVelocityTarget(digit->getDOF()); jointVelocityTarget.setZero(); jointNominalConfig << -0.0078, 0.0, 1.0283, 1.0, 0.0, 0.0, .0, // 7 0.314370, -0.036239, 0.320410, // 3 left-hip roll, pitch, yaw 0.985, -0.000, 0.003, 0.174, // U 4 (3) 0.358137, // 1 left-knee -0.0129, -0.3284, -0.0116, // U 3 left-shin, left-tarsus, left-heel-spring, -0.153398, // 1 left-toe-A 0.997, 0.0, 0.0, 0.078, // U 4 (3) left left rod 0.109565, // 1 left-toe-B 0.999, 0.0, 0.0, -0.052, // U 4 (3) left right rod 0.1266, -0.0486, // U 2 left-toe-pitch, left-toe-roll, -0.151641, 1.082777, 0.000251, -0.141862, // 4 left-shoulder-roll, left-shoulder-pitch, left-shoulder-yaw, left-elbow
Eigen::VectorXd jointPgain(digit->getDOF()), jointDgain(digit->getDOF()); int nJoints = digit->getDOF() - 6; std::cout<<nJoints<<std::endl;
jointPgain.setZero(); jointDgain.setZero(); jointPgain.tail(48).setConstant(100); jointDgain.tail(48).setConstant(100);
for (int i=0;i<3;i++) { jointPgain.tail(nJoints)[i+3]=0; jointPgain.tail(nJoints)[i+7]=0; jointPgain.tail(nJoints)[i+11]=0; jointPgain.tail(nJoints)[i+27]=0; jointPgain.tail(nJoints)[i+31]=0; jointPgain.tail(nJoints)[i+35]=0;
for (int i=0;i<5;i++) { jointPgain.tail(nJoints)[i+15]=0; jointPgain.tail(nJoints)[i+39]=0;
digit->setGeneralizedCoordinate(jointNominalConfig); digit->setPdGains(jointPgain, jointDgain); digit->setPdTarget(jointNominalConfig, jointVelocityTarget); digit->setName("digit"); Eigen::VectorXd gc, gv; gc.setZero(digit->getGeneralizedCoordinateDim()); gv.setZero(digit->getDOF());
server.launchServer(); for (int i=0; i<10000000; i++) { world.integrate(); std::this_thread::sleep_for(std::chrono::milliseconds(size_t(1000 * world.getTimeStep()))); } server.killServer(); }
##############Training image for RaisimGym######################