Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
64 changes: 63 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
# Jade

## Build and install Jade:
For python3.8 in linux, you can download wheel from realease.

See [instruction here](build_container/README.md). It builds a `manylinux_2_28`
To compile from source, see [instruction here](build_container/README.md). It builds a `manylinux_2_28`
wheel. You can install the wheel via `pip`.

## Tutorial:
Expand All @@ -11,6 +12,67 @@ See [tutorial of nimble](https://nimblephysics.org/docs/). Most APIs are the sam

**Attention**: Object geometry (defined in URDF) should be convex meshes, primitives like sphere and box are forbidden.

## GUI
Nimble API has its own limited GUI. To use bullet-based GUI, you need to install [pybullet](https://pybullet.org/wordpress/). You can install by running

`pip install pybullet`

After that, you can launch GUI after loading URDFs in code, visualize the states of Jade simluation and close the GUI by the below code.

```
gui = nimble.NimbleGUI(world, useBullet=True)
gui.loopStates(states)
gui.stopServing()
```

A `state` is combination of all joints of all skeletons in Jade. In `loopStates`, `states` refers to a collection of `state`, if you just want a single state, you can do a workaround by doing `states = [state]`. To debug and understand more about the state, you can do the below. Note that if you don't define a world-base joint in your urdf, Nimble will automatically add a 6D free joint `rootJoint` as your `state[:6]`
```
for i in range(world.getNumSkeletons()):
skel = world.getSkeleton(i)
joints = [[skel.getJoint(i) for i in range(skel.getNumJoints())]]
for joint in joints:
name, type = joint.getName(), joint.getType()
if type != 'WeldJoint': # Fixed joint
dof = joint.NumDofs
joint_value = joint.getPosistions()
```

If you want to use pybullet related functions you can use `gui.p` to access pybullet API, which is the same as `import pybullet as p` in normal setttings. For example, to change camera view, you can call. Note that instead of camera extrinsics, PyBullet uses the below form, where `target_pos` is the center point to area of interest, and the other three parameters describe relative information from camera to the point.
```
gui.p.resetDebugVisualizerCamera(dist, yaw, pitch, target_pos)
```

If you want to record the gui session, simply add the record path in the init argument as below
```
gui = nimble.NimbleGUI(world, useBullet=True, videoLogFile='path/to.mp4')
gui.loopStates(states)
gui.stopServing()
```

If you want to save synthetic camera output in `{depth/rgb/segmentation}_{index}.npy`, pass the save folder path during init argument as below. If you only want this and don't need the GUI window, pass `headless=True` when init the gui.
```
gui = nimble.NimbleGUI(world, useBullet=True, saveCameraPath='path/to/save/foler', headless=True)
```
If you need to do several loopStates and want to save the camera path together, you need to pass starting index when calling `loopStates`, otherwise it will by default start from `_0.npy`. For exmple, if you want to save the camera files starting with `_1000.npy`
```
gui.loopStates(states, save_start_idx=1000)
```

If you don't want to use the synthetic camera, disable it when init
```
gui = nimble.NimbleGUI(world, useBullet=True, useSyntheticCamera=False)
```

You can always open a new GUI after closing it, but if you just want to reset the gui, you can use the below function.

```
gui.bullet_reset(world)
```

You don't have to call other nimble GUI funcitons like `blockWhileServing`(no effect) or `nativeAPI` but calling these will not cause any problem or having any actual effects so it is easier for you to maintain multiple GUI settings.

Due to current limitaion, please refrain from manually changing your position and rotation when doing `world.loadSkeleton()`. If you met any problem regarding this, please raise an issue.

## Debug Mode:

Set environment variable `SPDLOG_LEVEL`. e.g., `SPDLOG_LEVEL=debug python myscripyt.py`.
Expand Down
64 changes: 51 additions & 13 deletions build_container/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -211,13 +211,51 @@ RUN pushd ezc3d && \
popd
RUN rm -rf ezc3d


################################# Alembic #################################
# Install imath
RUN git clone https://github.com/AcademySoftwareFoundation/Imath
RUN pushd Imath &&\
git checkout v3.1.9 &&\
mkdir build &&\
pushd build &&\
cmake .. &&\
make install &&\
popd && popd
RUN rm -rf Imath

# Install alembic
RUN git clone https://github.com/alembic/alembic.git
RUN pushd alembic &&\
git checkout 1.8.5 &&\
mkdir build &&\
pushd build &&\
cmake .. &&\
make install &&\
popd && popd
RUN rm -rf alembic

RUN git clone https://github.com/opencv/opencv.git
RUN pushd opencv &&\
git checkout 4.7.0 &&\
mkdir build &&\
pushd build &&\
cmake .. &&\
make -j4 &&\
make install &&\
popd && \
popd && \
rm -rf opencv


###########################################################################

# RUN ls /usr/local/lib64 | grep assimp
# RUN ls /usr/local/lib | grep assimp
# RUN rm -rf /usr/local/lib64/libassimp.so
# RUN rm -rf /usr/local/lib64/libassimp.5.so
# RUN rm -rf /usr/local/lib64/libassimp.5.0.1.so
RUN protoc --version

# Install spdlog
RUN git clone https://github.com/gabime/spdlog.git
RUN pushd spdlog &&\
Expand All @@ -229,7 +267,6 @@ RUN pushd spdlog &&\
popd &&\
popd
RUN rm -rf spdlog

# This is allowed to be empty string, but if it's not it must be prefixed by
ENV VERSION="0.7.7"

Expand Down Expand Up @@ -261,15 +298,16 @@ RUN ${PYTHON} -m pip install auditwheel
# ${PYTHON} -m auditwheel repair dist/nimblephysics-${VERSION}-${PYTHON_VERSION}-linux_x86_64.whl
# RUN mv /nimblephysics/wheelhouse/nimblephysics-${VERSION}-${PYTHON_VERSION}-manylinux_2_17_x86_64.manylinux2014_x86_64.whl /wheelhouse

ARG uid
ARG gid
ARG user=adamas
ARG group=adamas
ARG home=/home/${user}
RUN mkdir -p /etc/sudoers.d \
&& groupadd -g ${gid} ${group} \
&& useradd -d ${home} -u ${uid} -g ${gid} -m -s /bin/bash ${user}
USER ${user}
WORKDIR ${home}
ENV HOME ${home}
# ARG uid
# ARG gid
# ARG user=adamas
# ARG group=adamas
# ARG home=/home/${user}
# RUN mkdir -p /etc/sudoers.d \
# && groupadd -g ${gid} ${group} \
# && useradd -d ${home} -u ${uid} -g ${gid} -m -s /bin/bash ${user} \
# && echo "${user} ALL=(ALL) NOPASSWD:ALL" > /etc/sudoers.d/sudoers_${user}
# USER ${user}
# WORKDIR ${home}
# ENV HOME ${home}
COPY build_wheel.sh /usr/local/bin/build_wheel
15 changes: 15 additions & 0 deletions dart/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,21 @@ else()
target_compile_features(dart PUBLIC cxx_std_14)
endif()

# Add Alembic
find_package(Alembic REQUIRED PATHS "/usr/local/include/Alembic")
include_directories("/usr/local/include/Alembic")
include_directories("/usr/local/include/Imath")
target_include_directories(dart PRIVATE /usr/local/include/Imath)
target_link_libraries(dart PRIVATE Alembic::Alembic)

# Add Opencv
find_package(OpenCV REQUIRED COMPONENTS core imgcodecs)
include_directories( ${OpenCV_INCLUDE_DIRS} )
target_link_libraries( dart PRIVATE ${OpenCV_LIBS} )
# include_directories("/usr/local/include/opencv4")
# target_include_directories(dart PRIVATE /usr/local/include/opencv4)
# target_link_libraries(dart PRIVATE )

# Enable pthreads
set(THREADS_PREFER_PTHREAD_FLAG ON)
find_package(Threads REQUIRED)
Expand Down
24 changes: 24 additions & 0 deletions dart/dynamics/Skeleton.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,6 +404,30 @@ SkeletonPtr Skeleton::create(const AspectPropertiesData& properties)
return skel;
}

Eigen::Vector3s Skeleton::getBasePos() {
return base_pos;
}

Eigen::Vector3s Skeleton::getEulerAngle() {
return euler_angle;
}

std::string Skeleton::getURDFPath() {
return urdf_path;
}

void Skeleton::setBasePos(Eigen::Vector3s pos) {
base_pos = pos;
}

void Skeleton::setEulerAngle(Eigen::Vector3s angle) {
euler_angle = angle;
}

void Skeleton::setURDFPath(std::string path) {
urdf_path = path;
}

//==============================================================================
SkeletonPtr Skeleton::getPtr()
{
Expand Down
19 changes: 19 additions & 0 deletions dart/dynamics/Skeleton.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,12 @@ class Skeleton : public virtual common::VersionCounter,
public detail::SkeletonAspectBase
{
public:
std::string urdf_path;

Eigen::Vector3s base_pos;

Eigen::Vector3s euler_angle;

static Eigen::Matrix<s_t, Eigen::Dynamic, Eigen::Dynamic> EMPTY;

// Some of non-virtual functions of MetaSkeleton are hidden because of the
Expand Down Expand Up @@ -164,6 +170,18 @@ class Skeleton : public virtual common::VersionCounter,
/// Create a new Skeleton inside of a shared_ptr
static SkeletonPtr create(const AspectPropertiesData& properties);

Eigen::Vector3s getBasePos();

Eigen::Vector3s getEulerAngle();

std::string getURDFPath();

void setBasePos(Eigen::Vector3s pos);

void setEulerAngle(Eigen::Vector3s angle);

void setURDFPath(std::string string);

/// Get the shared_ptr that manages this Skeleton
SkeletonPtr getPtr();

Expand Down Expand Up @@ -2176,6 +2194,7 @@ class Skeleton : public virtual common::VersionCounter,
void addEntryToSoftBodyNodeNameMgr(SoftBodyNode* _newNode);

protected:

/// The resource-managing pointer to this Skeleton
std::weak_ptr<Skeleton> mPtr;

Expand Down
Loading