Skip to content

Commit

Permalink
unreal sensor implementations windows version
Browse files Browse the repository at this point in the history
  • Loading branch information
jhwangbo committed Jul 17, 2022
1 parent d67eb0b commit 96e5fc2
Show file tree
Hide file tree
Showing 71 changed files with 5,560 additions and 472 deletions.
12 changes: 0 additions & 12 deletions DEVELOPERS_ONLY/windowsInstall.ps1
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,4 @@ Set-Location C:\Users\jemin\source\repos\raisimLib\build
cmake .. -DRAISIM_EXAMPLE=ON -DRAISIM_PY=ON -DRAISIM_MATLAB=ON -DPYTHON_EXECUTABLE=C:\Users\jemin\anaconda3\envs\python35\python
cmake --build . --config Release

cmake .. -DRAISIM_EXAMPLE=ON -DRAISIM_PY=ON -DPYTHON_EXECUTABLE=C:\Users\jemin\anaconda3\envs\python36\python
cmake --build . --config Release

cmake .. -DRAISIM_EXAMPLE=ON -DRAISIM_PY=ON -DPYTHON_EXECUTABLE=C:\Users\jemin\anaconda3\envs\python37\python
cmake --build . --config Release

cmake .. -DRAISIM_EXAMPLE=ON -DRAISIM_PY=ON -DPYTHON_EXECUTABLE=C:\Users\jemin\anaconda3\envs\python38\python
cmake --build . --config Release

cmake .. -DRAISIM_EXAMPLE=ON -DRAISIM_PY=ON -DPYTHON_EXECUTABLE=C:\Users\jemin\anaconda3\envs\python39\python
cmake --build . --config Release

cd C:\Users\jemin
22 changes: 14 additions & 8 deletions examples/src/server/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,31 +33,37 @@ int main(int argc, char **argv) {
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.urdf");
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 depthSensor = anymal->getSensor<raisim::DepthCamera>("depth_camera_front_camera_parent/depth");
auto depthSensor = anymal->getSensor<raisim::DepthCamera>("depth_camera_front_camera_parent:depth");
depthSensor->setDataType(raisim::DepthCamera::DepthCameraProperties::DataType::COORDINATE);

server.launchServer();
std::vector<raisim::Visuals*> scans;
for(int i=0; i<depthSensor->getProperties().width; i++)
for(int j=0; j<depthSensor->getProperties().height; j++)
scans.push_back(server.addVisualBox("box" + std::to_string(i) + "/" + std::to_string(j), 0.03, 0.03, 0.03, 1, 0, 0));
// auto scans = server.addInstancedVisuals("scan points",
// raisim::InstancedVisuals::VisualBox,
// {0.05, 0.05, 0.05},
// {1,0,0,1},
// {0,1,0,1});
// scans->resize(depthSensor->getProperties().width * depthSensor->getProperties().height);

// std::vector<raisim::Visuals*> scans;
// for(int i=0; i<depthSensor->getProperties().width; i++)
// for(int j=0; j<depthSensor->getProperties().height; j++)
// scans.push_back(server.addVisualBox("box" + std::to_string(i) + "/" + std::to_string(j), 0.03, 0.03, 0.03, 1, 0, 0));

for (int k = 0; k < loopN; k++) {
world.integrate();
raisim::MSLEEP(world.getTimeStep() * 1000);
depthSensor->update(world);
auto& pos = depthSensor->get3DPoints();
for(int i=0; i<depthSensor->getProperties().width; i++)
for(int j=0; j<depthSensor->getProperties().height; j++) {
size_t id = i * depthSensor->getProperties().height + j;
scans[id]->setPosition(pos[id].e());
}
}

Expand Down
Binary file modified raisim/win32/mt_debug/bin/atlas.exe
Binary file not shown.
Binary file modified raisim/win32/mt_debug/bin/atlas.ilk
Binary file not shown.
Binary file modified raisim/win32/mt_debug/bin/atlas.pdb
Binary file not shown.
Binary file modified raisim/win32/mt_debug/bin/raisim.dll
Binary file not shown.
10 changes: 5 additions & 5 deletions raisim/win32/mt_debug/bin/rsc/anymal_c/sensors/realsense435.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<!-- <box size="0.0078 0.130 0.0192"/>-->
<!-- </geometry>-->
<!-- </collision>-->
<sensor name="color" type="rgb">
<sensor name="color" type="rgb" update_rate="20">
<origin rpy="0.0 0.0 0.0" xyz="0 -0.046 0.004"/>
<camera horizontal_fov="1.047">
<image width="640" height="480"/>
Expand All @@ -29,7 +29,7 @@
</camera>
<update_rate>60</update_rate>
</sensor>
<sensor name="ired1" type="camera">
<sensor name="ired1" type="camera" update_rate="20">
<origin rpy="0.0 0.0 0.0" xyz="0 -0.06 0.004"/>
<camera horizontal_fov="1.047">
<image width="640" height="480"/>
Expand All @@ -38,19 +38,19 @@
</camera>
<update_rate>60</update_rate>
</sensor>
<sensor name="ired2" type="camera">
<sensor name="ired2" type="camera" update_rate="20">
<origin rpy="0.0 0.0 0.0" xyz="0 0.01 0.004"/>
<camera horizontal_fov="1.047">
<image width="640" height="480"/>
<clip near="0.1" far="100"/>
<noise type="gaussian" mean="0.0" stddev="0.007"/>
</camera>
</sensor>
<sensor name="depth" type="depth">
<sensor name="depth" type="depth" update_rate="20">
<data type="coordinates"/>
<origin rpy="0.0 0.0 0.0" xyz="0 -0.03 0.004"/>
<camera horizontal_fov="1.047">
<image width="6" height="4"/>
<image width="640" height="480"/>
<clip near="0.1" far="100"/>
<noise type="gaussian" mean="0.0" stddev="0.007"/>
</camera>
Expand Down
2 changes: 1 addition & 1 deletion raisim/win32/mt_debug/bin/rsc/anymal_c/urdf/anymal.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,7 @@
<origin rpy="0.0 0.0 0.0" xyz="0.0255 0.0175 0.0"/>
</joint>
<!-- Camera parent link -->
<link name="depth_camera_front_camera_parent" sensor="realsense435.xml"/>
<link name="depth_camera_front_camera_parent"/>
<!-- Depth optical frame joint -->
<joint name="depth_camera_front_camera_parent_to_depth_optical_frame" type="fixed">
<parent link="depth_camera_front_camera_parent"/>
Expand Down
Loading

0 comments on commit 96e5fc2

Please sign in to comment.