Skip to content

Commit

Permalink
Updrake (#50)
Browse files Browse the repository at this point in the history
* Fix drake deprecation

* Update CI

* Update cmakelists

* Update readme

* Install yaml docker
  • Loading branch information
pangtao22 authored Aug 2, 2023
1 parent a5f0678 commit 52e3ffa
Show file tree
Hide file tree
Showing 8 changed files with 33 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,5 @@ description: 'runs tests.'

runs:
using: 'docker'
image: '../../../bionic.dockerfile'
image: '../../../jammy.dockerfile'
entrypoint: './scripts/build_test.sh'
12 changes: 6 additions & 6 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,23 +8,23 @@ on:
- cron: "0 6 * * *" # 6am everyday.

jobs:
bionic:
focal:
runs-on: ubuntu-latest
steps:
# To use this repository's private action,
# you must check out the repository
- name: Checkout
uses: actions/checkout@v2
uses: actions/checkout@v3
- name: build and test action step
uses: ./.github/actions/bionic
uses: ./.github/actions/focal
id: build_test
focal:
jammy:
runs-on: ubuntu-latest
steps:
# To use this repository's private action,
# you must check out the repository
- name: Checkout
uses: actions/checkout@v2
uses: actions/checkout@v3
- name: build and test action step
uses: ./.github/actions/focal
uses: ./.github/actions/jammy
id: build_test
11 changes: 6 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ if(NOT APPLE)
)
endif()

if(NOT UNIX_DISTRIBUTION_CODENAME MATCHES "^(bionic|focal)$")
if(NOT UNIX_DISTRIBUTION_CODENAME MATCHES "^(focal|jammy)$")
message(FATAL_ERROR
"Release ${UNIX_DISTRIBUTION_CODENAME} is NOT supported. Please use "
"Ubuntu 18.04 (Bionic) or 20.04 (Focal)."
Expand All @@ -82,13 +82,14 @@ endif()

if(APPLE)
set(FIND_PYTHON_EXECUTABLE_PATHS /usr/local/bin)
set(FIND_PYTHON_INTERP_VERSION 3.9)
elseif(UNIX_DISTRIBUTION_CODENAME STREQUAL bionic)
set(FIND_PYTHON_INTERP_VERSION 3.11)
elseif(UNIX_DISTRIBUTION_CODENAME STREQUAL focal)
set(FIND_PYTHON_EXECUTABLE_PATHS /usr/bin)
set(FIND_PYTHON_INTERP_VERSION 3.6)
set(FIND_PYTHON_INTERP_VERSION 3.8)
else()
# Jammy
set(FIND_PYTHON_EXECUTABLE_PATHS /usr/bin)
set(FIND_PYTHON_INTERP_VERSION 3.8)
set(FIND_PYTHON_INTERP_VERSION 3.10)
endif()
find_program(PYTHON_EXECUTABLE NAMES python3
PATHS "${FIND_PYTHON_EXECUTABLE_PATHS}"
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,6 @@ An incomplete design documentation can be found [here](https://slides.com/pang/d

## Continuous Integration
- CI is implemented by a custom Github Action that builds a docker image
using `./bionic.dockerfile` and runs the entrypoint script `.
using `./jammy.dockerfile` and runs the entrypoint script `.
/sciprts/buld_test.sh`.

7 changes: 4 additions & 3 deletions focal.dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,14 @@ FROM ubuntu:20.04
ENV DEBIAN_FRONTEND=noninteractive
RUN apt-get update && yes "Y" \
| apt-get install --no-install-recommends curl apt-transport-https sudo \
ca-certificates libgtest-dev libgflags-dev python3-dev\
ca-certificates libgtest-dev libgflags-dev python3.8-dev python-is-python3 \
libyaml-cpp-dev \
&& rm -rf /var/lib/apt/lists/* \
&& apt-get clean all

# install drake.
ENV DRAKE_URL=https://drake-packages.csail.mit.edu/drake/nightly/drake-latest-focal.tar.gz
RUN curl -o drake.tar.gz $DRAKE_URL
ENV DRAKE_URL=https://github.com/RobotLocomotion/drake/releases/download/v1.19.0/drake-20230713-focal.tar.gz
RUN curl -L -o drake.tar.gz $DRAKE_URL
RUN tar -xzf drake.tar.gz -C /opt && rm drake.tar.gz
RUN apt-get update \
&& yes "Y" | bash /opt/drake/share/drake/setup/install_prereqs \
Expand Down
9 changes: 5 additions & 4 deletions bionic.dockerfile → jammy.dockerfile
Original file line number Diff line number Diff line change
@@ -1,15 +1,16 @@
FROM ubuntu:18.04
FROM ubuntu:22.04

# Install curl and useful transport
ENV DEBIAN_FRONTEND=noninteractive
RUN apt-get update && yes "Y" \
| apt-get install --no-install-recommends curl apt-transport-https sudo \
ca-certificates libgtest-dev libgflags-dev \
ca-certificates libgtest-dev libgflags-dev python3.10-dev python-is-python3 \
libyaml-cpp-dev \
&& rm -rf /var/lib/apt/lists/* \
&& apt-get clean all

# install drake.
ENV DRAKE_URL=https://github.com/RobotLocomotion/drake/releases/download/v1.1.0/drake-20220328-bionic.tar.gz
ENV DRAKE_URL=https://github.com/RobotLocomotion/drake/releases/download/v1.19.0/drake-20230713-jammy.tar.gz
RUN curl -L -o drake.tar.gz $DRAKE_URL
RUN tar -xzf drake.tar.gz -C /opt && rm drake.tar.gz
RUN apt-get update \
Expand All @@ -22,4 +23,4 @@ COPY scripts/install_cppzmq.sh /install_dependencies.sh
RUN /bin/bash /install_dependencies.sh

# put drake on the python path.
ENV PYTHONPATH /opt/drake/lib/python3.6/site-packages:$PYTHONPATH
ENV PYTHONPATH /opt/drake/lib/python3.10/site-packages:$PYTHONPATH
13 changes: 6 additions & 7 deletions src/plans/task_space_trajectory_plan.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@
using drake::MatrixX;
using drake::Vector3;
using drake::Vector6;
using drake::manipulation::planner::ComputePoseDiffInCommonFrame;
using drake::manipulation::planner::DifferentialInverseKinematicsResult;
using drake::manipulation::planner::DifferentialInverseKinematicsStatus;
using drake::manipulation::planner::internal::DoDifferentialInverseKinematics;
using drake::multibody::ComputePoseDiffInCommonFrame;
using drake::multibody::DifferentialInverseKinematicsResult;
using drake::multibody::DifferentialInverseKinematicsStatus;
using drake::multibody::DoDifferentialInverseKinematics;

using std::cout;
using std::endl;
Expand All @@ -29,16 +29,15 @@ void TaskSpaceTrajectoryPlan::Step(const State &state, double control_period,

const Vector6<double> V_WT_desired =
ComputePoseDiffInCommonFrame(X_WT, X_WT_desired) /
params_->get_timestep();
params_->get_time_step();

MatrixX<double> J_WT(6, plant_->num_velocities());
plant_->CalcJacobianSpatialVelocity(
*plant_context_, drake::multibody::JacobianWrtVariable::kV, frame_E_,
X_ET_.translation(), frame_W, frame_W, &J_WT);

DifferentialInverseKinematicsResult result = DoDifferentialInverseKinematics(
state.q, state.v, X_WT, J_WT,
drake::multibody::SpatialVelocity<double>(V_WT_desired), *params_);
state.q, state.v, V_WT_desired, J_WT, *params_);

// 3. Check for errors and integrate.
if (result.status != DifferentialInverseKinematicsStatus::kSolutionFound) {
Expand Down
8 changes: 4 additions & 4 deletions src/plans/task_space_trajectory_plan.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

#include "drake/common/trajectories/piecewise_polynomial.h"
#include "drake/common/trajectories/piecewise_quaternion.h"
#include "drake/manipulation/planner/differential_inverse_kinematics_integrator.h"
#include "drake/multibody/inverse_kinematics/differential_inverse_kinematics_integrator.h"
#include "drake/math/rigid_transform.h"
#include "drake/multibody/plant/multibody_plant.h"
#include "drake/multibody/tree/multibody_tree.h"
Expand All @@ -26,9 +26,9 @@ class TaskSpaceTrajectoryPlan : public PlanBase {
frame_E_(frame_E), nominal_joint_position_(nominal_joint_position) {

params_ = std::make_unique<
drake::manipulation::planner::DifferentialInverseKinematicsParameters>(
drake::multibody::DifferentialInverseKinematicsParameters>(
plant_->num_positions(), plant_->num_velocities());
params_->set_timestep(control_time_step);
params_->set_time_step(control_time_step);
params_->set_nominal_joint_position(nominal_joint_position);
plant_context_ = plant_->CreateDefaultContext();
}
Expand All @@ -53,6 +53,6 @@ class TaskSpaceTrajectoryPlan : public PlanBase {

std::unique_ptr<drake::systems::Context<double>> plant_context_;
std::unique_ptr<
drake::manipulation::planner::DifferentialInverseKinematicsParameters>
drake::multibody::DifferentialInverseKinematicsParameters>
params_;
};

0 comments on commit 52e3ffa

Please sign in to comment.