Skip to content

Commit

Permalink
[drake_cmake_installed] Replace broken particles example (#355)
Browse files Browse the repository at this point in the history
For now, just sync up with the drake_cmake_installed_apt example.
It is not a great demo, but it's what we have.
  • Loading branch information
jwnimmer-tri authored Jan 17, 2025
1 parent b8e2687 commit b200975
Show file tree
Hide file tree
Showing 22 changed files with 150 additions and 385 deletions.
2 changes: 1 addition & 1 deletion drake_cmake_installed/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ execute_process(COMMAND ${Python3_EXECUTABLE}-config --exec-prefix
)
list(APPEND CMAKE_PREFIX_PATH "${PYTHON_EXEC_PREFIX}")

get_filename_component(PYTHONPATH
get_filename_component(DRAKE_PYTHONPATH
"${drake_DIR}/../../python${Python3_VERSION_MAJOR}.${Python3_VERSION_MINOR}/site-packages"
REALPATH
)
Expand Down
10 changes: 1 addition & 9 deletions drake_cmake_installed/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -49,14 +49,6 @@ cd drake-external-examples
mkdir drake_cmake_installed-build && cd drake_cmake_installed-build
cmake -DCMAKE_PREFIX_PATH=$HOME/drake ../drake_cmake_installed
make

###############################################################
# Execute
###############################################################
# A demo
$HOME/drake/bin/drake-visualizer &
(cd src/particles && exec ./uniformly_accelerated_particle)

# (Optionally) Run Tests
make test
```
Expand All @@ -66,7 +58,7 @@ make test
Drake specific Examples:

* [Simple Continuous Time System](src/simple_continuous_time_system/README.md)
* [Particle Demo](src/particles/README.md)
* [Particle System](src/particle)
* [Find Resources](src/find_resource/README.md)

# Developer Testing
Expand Down
4 changes: 0 additions & 4 deletions drake_cmake_installed/setup/Brewfile

This file was deleted.

6 changes: 1 addition & 5 deletions drake_cmake_installed/setup/install_prereqs
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,6 @@ case "$OSTYPE" in
curl -o drake.tar.gz https://drake-packages.csail.mit.edu/drake/nightly/drake-latest-mac-arm64.tar.gz
trap 'rm -f drake.tar.gz' EXIT
tar -xf drake.tar.gz -C /opt

# Install additional dependencies needed to build example
brew bundle --file="$(dirname "${BASH_SOURCE}")/Brewfile"
;;

linux*)
Expand Down Expand Up @@ -83,7 +80,6 @@ EOF

apt-get update
apt-get install --no-install-recommends $(cat <<EOF
libgflags-dev
python3-all-dev
EOF
)
Expand All @@ -93,4 +89,4 @@ esac
# Show version for debugging; use echo for newline / readability.
echo -e "\ndrake VERSION.TXT: $(cat /opt/drake/share/doc/drake/VERSION.TXT)\n"

/opt/drake/share/drake/setup/install_prereqs
/opt/drake/share/drake/setup/install_prereqs
4 changes: 2 additions & 2 deletions drake_cmake_installed/src/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
# SPDX-License-Identifier: MIT-0

add_subdirectory(find_resource)
add_subdirectory(particles)
add_subdirectory(particle)
add_subdirectory(simple_bindings)
add_subdirectory(simple_continuous_time_system)

add_test(NAME import_all_test COMMAND
"${Python3_EXECUTABLE}" "${CMAKE_CURRENT_SOURCE_DIR}/import_all_test.py"
)
set_tests_properties(import_all_test PROPERTIES
ENVIRONMENT "PYTHONPATH=${PYTHONPATH}"
ENVIRONMENT "PYTHONPATH=${DRAKE_PYTHONPATH}"
)
2 changes: 1 addition & 1 deletion drake_cmake_installed/src/find_resource/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,5 @@ add_test(NAME find_resource_example_py COMMAND
"${Python3_EXECUTABLE}" "${CMAKE_CURRENT_SOURCE_DIR}/find_resource_example.py"
)
set_tests_properties(find_resource_example_py PROPERTIES
ENVIRONMENT "PYTHONPATH=${PYTHONPATH}"
ENVIRONMENT "PYTHONPATH=${DRAKE_PYTHONPATH}"
)
20 changes: 20 additions & 0 deletions drake_cmake_installed/src/particle/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# SPDX-License-Identifier: MIT-0

add_library(particle particle.cc particle.h)
target_link_libraries(particle drake::drake)

add_executable(particle_test particle_test.cc)
target_link_libraries(particle_test particle drake::drake gtest)
add_test(NAME cc_particle_test COMMAND particle_test)
set_tests_properties(cc_particle_test PROPERTIES LABELS small TIMEOUT 60)

add_test(NAME python_particle_test
COMMAND Python3::Interpreter -B -m unittest particle_test
)
set_tests_properties(python_particle_test PROPERTIES
ENVIRONMENT "PYTHONPATH=${DRAKE_PYTHONPATH}"
LABELS small
REQUIRED_FILES "${CMAKE_CURRENT_SOURCE_DIR}/particle_test.py"
TIMEOUT 60
WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}"
)
Original file line number Diff line number Diff line change
Expand Up @@ -22,19 +22,14 @@ namespace particles {
/// - linear position (state/output index 0), in @f$ m @f$ units.
/// - linear velocity (state/output index 1), in @f$ m/s @f$ units.
///
/// @tparam T must be a valid Eigen ScalarType.
///
/// @note
/// Instantiated templates for the following scalar types
/// @p T are provided:
///
/// - double
/// @tparam_double_only
///
template <typename T>
class Particle final : public drake::systems::LeafSystem<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Particle);

/// A constructor that initializes the system.
Particle();

protected:
Expand Down
48 changes: 48 additions & 0 deletions drake_cmake_installed/src/particle/particle.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
# SPDX-License-Identifier: MIT-0

from pydrake.systems.framework import BasicVector
from pydrake.systems.framework import LeafSystem
from pydrake.systems.framework import PortDataType


class Particle(LeafSystem):
"""
A linear 1DOF particle system.
With very simple dynamics xdotdot = a, this system can be described in
terms of its:
Inputs:
linear acceleration (input index 0), in m/s^2 units.
States/Outputs:
linear position (state/output index 0), in m units.
linear velocity (state/output index 1), in m/s units.
"""
def __init__(self):
LeafSystem.__init__(self)
# A 1D input vector for acceleration.
self.DeclareInputPort('acceleration', PortDataType.kVectorValued, 1)
# Adding one generalized position and one generalized velocity.
self.DeclareContinuousState(1, 1, 0)
# A 2D output vector for position and velocity.
self.DeclareVectorOutputPort('postion_and_velocity', BasicVector(2),
self.CopyStateOut)

def CopyStateOut(self, context, output):
# Get current state from context.
continuous_state_vector = context.get_continuous_state_vector()
# Write system output.
output.SetFromVector(continuous_state_vector.CopyToVector())

def DoCalcTimeDerivatives(self, context, derivatives):
# Get current state from context.
continuous_state_vector = x = context.get_continuous_state_vector()
# Obtain the structure we need to write into.
derivatives_vector = derivatives.get_mutable_vector()
# Get current input acceleration value.
input_vector = self.EvalVectorInput(context, 0)
# Set the derivatives. The first one is velocity and the second one is
# acceleration.
derivatives_vector.SetAtIndex(0, continuous_state_vector.GetAtIndex(1))
derivatives_vector.SetAtIndex(1, input_vector.GetAtIndex(0))
59 changes: 59 additions & 0 deletions drake_cmake_installed/src/particle/particle_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
# SPDX-License-Identifier: MIT-0

import unittest

from particle import Particle


class TestParticle(unittest.TestCase):
"""A test case for Particle systems."""
def setUp(self):
# System (aka 'device under test') being tested.
self.dut = Particle()
# Context for the given dut.
self.context = self.dut.CreateDefaultContext()
# Outputs of the given dut.
self.output = self.dut.AllocateOutput()
# Derivatives of the given dut.
self.derivatives = self.dut.AllocateTimeDerivatives()

def test_output(self):
"""
Makes sure a Particle output is consistent with its state (position and
velocity).
"""
# Initialize state.
continuous_state_vector = \
self.context.get_mutable_continuous_state_vector()
continuous_state_vector.SetAtIndex(0, 10.0) # x0 = 10 m.
continuous_state_vector.SetAtIndex(1, 1.0) # x1 = 1 m/s.
# Compute outputs.
self.dut.CalcOutput(self.context, self.output)
output_vector = self.output.get_vector_data(0)
# Check results.
self.assertEqual(output_vector.GetAtIndex(0), 10.0) # y0 == x0
self.assertEqual(output_vector.GetAtIndex(1), 1.0) # y1 == x1

def test_derivatives(self):
"""
Makes sure a Particle system state derivatives are consistent with its
state and input (velocity and acceleration).
"""
# Set input.
input_port = self.dut.get_input_port(0)
input_port.FixValue(self.context, 1.0) # u0 = 1 m/s^2
# Set state.
continuous_state_vector = \
self.context.get_mutable_continuous_state_vector()
continuous_state_vector.SetAtIndex(0, 0.0) # x0 = 0 m
continuous_state_vector.SetAtIndex(1, 2.0) # x1 = 2 m/s
# Compute derivatives.
self.dut.CalcTimeDerivatives(self.context, self.derivatives)
derivatives_vector = self.derivatives.get_vector()
# Check results.
self.assertEqual(derivatives_vector.GetAtIndex(0), 2.0) # x0dot == x1
self.assertEqual(derivatives_vector.GetAtIndex(1), 1.0) # x1dot == u0


if __name__ == '__main__':
unittest.main()
25 changes: 0 additions & 25 deletions drake_cmake_installed/src/particles/CMakeLists.txt

This file was deleted.

33 changes: 0 additions & 33 deletions drake_cmake_installed/src/particles/README.md

This file was deleted.

Binary file not shown.
40 changes: 0 additions & 40 deletions drake_cmake_installed/src/particles/models/particle.sdf

This file was deleted.

Loading

0 comments on commit b200975

Please sign in to comment.