Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#8601 from RussTedrake/compass_gait2
Browse files Browse the repository at this point in the history
Adds compass gait example
  • Loading branch information
RussTedrake authored Apr 25, 2018
2 parents 1bf1ad7 + e08d2e7 commit e606386
Show file tree
Hide file tree
Showing 11 changed files with 1,182 additions and 8 deletions.
1 change: 1 addition & 0 deletions examples/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ INSTALLED_MODEL_PACKAGES = [
"//examples/acrobot",
"//examples/atlas",
"//examples/contact_model",
"//examples/compass_gait",
"//examples/double_pendulum",
"//examples/irb140",
"//examples/kuka_iiwa_arm",
Expand Down
72 changes: 72 additions & 0 deletions examples/compass_gait/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
# -*- python -*-

load(
"//tools:drake.bzl",
"drake_cc_googletest",
"drake_cc_library",
"drake_cc_binary",
)
load("//tools/install:install_data.bzl", "install_data")
load("//tools/lint:lint.bzl", "add_lint_tests")
load(
"@drake//tools/vector_gen:vector_gen.bzl",
"drake_cc_vector_gen_library",
)

package(default_visibility = ["//visibility:public"])

drake_cc_vector_gen_library(
name = "compass_gait_vector_types",
srcs = [
"compass_gait_continuous_state.named_vector",
"compass_gait_params.named_vector",
],
visibility = ["//visibility:public"],
)

drake_cc_library(
name = "compass_gait",
srcs = ["compass_gait.cc"],
hdrs = [
"compass_gait.h",
],
deps = [
":compass_gait_vector_types",
"//common:default_scalars",
"//common:essential",
"//systems/framework:leaf_system",
],
)

drake_cc_binary(
name = "simulate",
srcs = ["simulate.cc"],
add_test_rule = 1,
data = ["CompassGait.urdf"],
test_rule_args = ["--target_realtime_rate=0.0"],
deps = [
":compass_gait",
"//common:find_resource",
"//lcm",
"//math:geometric_transform",
"//multibody:rigid_body_tree",
"//multibody/parsers",
"//multibody/rigid_body_plant:drake_visualizer",
"//systems/analysis:simulator",
"@gflags",
],
)

drake_cc_googletest(
name = "compass_gait_test",
data = ["CompassGait.urdf"],
deps = [
":compass_gait",
"//common/test_utilities:eigen_matrix_compare",
"//systems/framework/test_utilities:scalar_conversion",
],
)

install_data()

add_lint_tests()
112 changes: 112 additions & 0 deletions examples/compass_gait/CompassGait.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from CompassGait.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="CompassGait" xmlns="http://drake.mit.edu" xmlns:xacro="http://ros.org/wiki/xacro" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:schemaLocation="http://drake.mit.edu ../../../doc/drakeURDF.xsd">
<link name="world">
</link>
<link name="hip">
<inertial>
<mass value="10"/>
<!-- inertia is zero, which is the default -->
</inertial>
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material>
<color rgba="0 1 0 1"/>
</material>
</visual>
</link>
<joint name="floating_base" type="planar">
<parent link="world"/>
<child link="hip"/>
<axis xyz="0 1 0"/>
</joint>
<link name="left_leg">
<visual>
<origin xyz="0 0 -0.5"/>
<geometry>
<cylinder length="1.0" radius="0.0075"/>
</geometry>
<material>
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -1.0"/>
<geometry>
<sphere radius="0"/>
</geometry>
</collision>
</link>
<link name="left_leg_mass">
<visual>
<origin xyz="0 0 -0.5"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material>
<color rgba="1 0 0 1"/>
</material>
</visual>
<inertial>
<origin xyz="0 0 -0.5"/>
<mass value="5"/>
<!-- zero inertia -->
</inertial>
</link>
<joint name="left_leg_mass_weld" type="fixed">
<parent link="left_leg"/>
<child link="left_leg_mass"/>
</joint>
<link name="right_leg">
<visual>
<origin xyz="0 0 -0.5"/>
<geometry>
<cylinder length="1.0" radius="0.0075"/>
</geometry>
<material>
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -1.0"/>
<geometry>
<sphere radius="0"/>
</geometry>
</collision>
</link>
<link name="right_leg_mass">
<visual>
<origin xyz="0 0 -0.5"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material>
<color rgba="0 0 1 1"/>
</material>
</visual>
<inertial>
<origin xyz="0 0 -0.5"/>
<mass value="5"/>
<!-- zero inertia -->
</inertial>
</link>
<joint name="right_leg_mass_weld" type="fixed">
<parent link="right_leg"/>
<child link="right_leg_mass"/>
</joint>
<joint name="left_leg_weld" type="fixed">
<parent link="hip"/>
<child link="left_leg"/>
</joint>
<joint name="hip_pin" type="continuous">
<parent link="hip"/>
<child link="right_leg"/>
<axis xyz="0 1 0"/>
</joint>
</robot>

90 changes: 90 additions & 0 deletions examples/compass_gait/CompassGait.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
<?xml version="1.0"?>

<robot xmlns="http://drake.mit.edu"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="http://drake.mit.edu ../../../doc/drakeURDF.xsd"
xmlns:xacro="http://ros.org/wiki/xacro" name="CompassGait">

<xacro:property name="mh" value="10" />
<xacro:property name="m" value="5" />
<xacro:property name="a" value=".5" />
<xacro:property name="b" value=".5" />

<xacro:macro name="leg" params="lr color">
<link name="${lr}_leg">
<visual>
<origin xyz="0 0 ${-(a+b)/2}" />
<geometry>
<cylinder radius="0.0075" length="${a+b}"/>
</geometry>
<material>
<color rgba="${color}" />
</material>
</visual>
<collision>
<origin xyz="0 0 ${-a-b}" />
<geometry>
<sphere radius="0"/>
</geometry>
</collision>
</link>
<link name="${lr}_leg_mass">
<visual>
<origin xyz="0 0 ${-a}" />
<geometry>
<sphere radius="${.01*m}" />
</geometry>
<material>
<color rgba="${color}" />
</material>
</visual>
<inertial>
<origin xyz="0 0 ${-a}" />
<mass value="${m}" />
<!-- zero inertia -->
</inertial>
</link>
<joint name="${lr}_leg_mass_weld" type="fixed">
<parent link="${lr}_leg" />
<child link="${lr}_leg_mass" />
</joint>
</xacro:macro>

<link name="world">
</link>
<link name="hip">
<inertial>
<mass value="${mh}" />
<!-- inertia is zero, which is the default -->
</inertial>
<visual>
<geometry>
<sphere radius="${.005*mh}" />
</geometry>
<material>
<color rgba="0 1 0 1" />
</material>
</visual>
</link>

<joint name="floating_base" type="planar">
<parent link="world" />
<child link="hip" />
<axis xyz="0 1 0" />
</joint>

<xacro:leg lr="left" color="1 0 0 1" />
<xacro:leg lr="right" color="0 0 1 1" />

<joint name="left_leg_weld" type="fixed">
<parent link="hip" />
<child link="left_leg" />
</joint>

<joint name="hip_pin" type="continuous">
<parent link="hip" />
<child link="right_leg" />
<axis xyz="0 1 0"/>
</joint>

</robot>
Loading

0 comments on commit e606386

Please sign in to comment.