Server Example: Synchronous Server Update
Overview
Runs the RaisimServer in a manual socket loop and updates sensors only when the client requests them. This shows how to drive synchronous visualization and sensor updates.
Binary
CMake target and executable name: synchronous_server_update.
Run
Build and run from your build directory:
cmake --build . --target synchronous_server_update
./synchronous_server_update
On Windows, run synchronous_server_update.exe instead.
This example uses RaisimServer. Start a visualizer client (RaisimUnity, RaisimUnreal, or the rayrai TCP viewer) and connect to port 8080.
Details
Runs RaisimServer in synchronous request/response mode.
Manually accepts a TCP connection and processes sensor update requests.
Uses VISUALIZER RGB/depth sensors with
needsSensorUpdate().
Source
//
// Created by jemin on 2022-07-21.
//
#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 int loopN = 200000000;
raisim::RaiSimMsg::setFatalCallback([](){throw;}); /// this will ensure that throw is called upon error
raisim::World world;
raisim::RaisimServer server(&world);
auto checkerBoard = world.addGround(0.0, "glass");
Eigen::VectorXd jointConfig(19), jointVelocityTarget(18);
Eigen::VectorXd jointState(18), jointVel(18), jointPgain(18), jointDgain(18);
jointPgain.setZero();
jointPgain.tail(12).setConstant(200.0);
jointDgain.setZero();
jointDgain.tail(12).setConstant(10.0);
jointVelocityTarget.setZero();
jointConfig << 0, 0, 0.54, 1, 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;
jointVel << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0;
auto anymal = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal_c\\urdf\\anymal_sensored.urdf");
anymal->setState(jointConfig, jointVel);
anymal->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE);
anymal->setPdGains(jointPgain, jointDgain);
anymal->setPdTarget(jointConfig, jointVelocityTarget);
anymal->setGeneralizedForce(Eigen::VectorXd::Zero(anymal->getDOF()));
anymal->setName("Anymal");
auto front_depthSensor = anymal->getSensorSet("depth_camera_rear_camera_parent")->getSensor<raisim::DepthCamera>("depth");
front_depthSensor->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
auto front_rgbCamera = anymal->getSensorSet("depth_camera_front_camera_parent")->getSensor<raisim::RGBCamera>("color");
front_rgbCamera->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
auto rear_depthSensor = anymal->getSensorSet("depth_camera_rear_camera_parent")->getSensor<raisim::DepthCamera>("depth");
rear_depthSensor->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
auto rear_rgbCamera = anymal->getSensorSet("depth_camera_rear_camera_parent")->getSensor<raisim::RGBCamera>("color");
rear_rgbCamera->setMeasurementSource(raisim::Sensor::MeasurementSource::VISUALIZER);
server.setupSocket();
raisim_examples::warnIfNoClientConnected(server);
server.acceptConnection(2000.0);
for (int k = 0; k < loopN; k++) {
server.applyInteractionForce();
world.integrate();
if (server.needsSensorUpdate()) {
if (server.waitForMessageFromClient(1.0)) {
if (!server.processRequests()) {
server.acceptConnection(2000.0);
}
}
}
}
server.closeConnection();
return 0;
}