Skip to content

Instantly share code, notes, and snippets.

@michalpelka
Created April 23, 2025 16:14
Show Gist options
  • Save michalpelka/b0e410ee5c0e6157f48a1eef3c9ebd5d to your computer and use it in GitHub Desktop.
Save michalpelka/b0e410ee5c0e6157f48a1eef3c9ebd5d to your computer and use it in GitHub Desktop.
Minimal Drake C++ example
cmake_minimum_required(VERSION 3.26)
project(drake_project)
# N.B. This is a temporary flag. It only really applies to Linux, as Mac
# does not need X11.
option(RUN_X11_TESTS "Run tests that require X11" OFF)
include(CTest)
set (drake_DIR /home/michalpelka/physics/drake-build/install/lib/cmake/drake/)
find_package(drake CONFIG REQUIRED)
find_package(Gflags REQUIRED)
find_package(Glog REQUIRED)
message(STATUS "GFLAGS include path: ${GFLAGS_INCLUDE_DIR}")
set(CMAKE_CXX_EXTENSIONS OFF)
set(CMAKE_CXX_STANDARD 20)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
add_executable(drake_project DrakeHello.cpp)
target_link_libraries(drake_project PRIVATE drake::drake ${GFLAGS_LIBRARIES} )
#include <iostream>
#include <gflags/gflags.h>
#include "drake/multibody/benchmarks/inclined_plane/inclined_plane_plant.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/multibody/parsing/parser.h"
const char* dropped_ball_xml = R"(
<mujoco model="dropped_ball">
<option gravity="0 0 -9.81"/>
<worldbody>
<!-- Ground plane -->
<geom name="floor" type="plane" pos="0 0 -1" size="5 5 0.1" rgba="0.2 0.3 0.4 1"/>
<!-- Dropped ball -->
<body name="ball" pos="0 0 2">
<joint type="free"/>
<geom type="sphere" size="0.1" rgba="1 0 0 1"/>
</body>
</worldbody>
</mujoco>
)";
int main ()
{
using namespace drake;
drake::systems::DiagramBuilder<double> builder;
using drake::multibody::MultibodyPlant;
drake::multibody::MultibodyPlantConfig plant_config;
plant_config.time_step = 0.0001;
plant_config.stiction_tolerance = 1.0E-5;
plant_config.discrete_contact_approximation = "tamsi";
auto [plant, scene_graph] = multibody::AddMultibodyPlantSceneGraph(&builder, 0.0);
multibody::Parser parser(&plant);
parser.AddModelsFromString(dropped_ball_xml, "xml");
plant.Finalize();
std::cout << "number of bodies " << plant.num_bodies() << std::endl;
auto diagram = builder.Build();
systems::Simulator<double> simulator(*diagram);
simulator.Initialize();
auto& plant_context = diagram->GetMutableSubsystemContext(plant, &simulator.get_mutable_context());
const double dt = 0.01;
for (int i =0; i < 1000; i++)
{
simulator.AdvanceTo(i*dt);
const auto& body = plant.get_body(drake::multibody::BodyIndex(1));
auto X_WB = plant.EvalBodyPoseInWorld(plant_context, body);
auto p = X_WB.translation();
std::cout << " " << body.name() << ": (" << p[0] << ", " << p[1] << ", " << p[2] << ")" << std::endl;
}
}
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment