-
Notifications
You must be signed in to change notification settings - Fork 1.3k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
9f6a582
commit 7c074fd
Showing
2 changed files
with
158 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,10 +1,39 @@ | ||
# -*- python -*- | ||
# This file contains rules for Bazel; see drake/doc/bazel.rst. | ||
|
||
load("//tools/install:install_data.bzl", "install_data") | ||
load( | ||
"@drake//tools/skylark:drake_cc.bzl", | ||
"drake_cc_binary", | ||
) | ||
load("//tools/lint:lint.bzl", "add_lint_tests") | ||
load("//tools/install:install_data.bzl", "install_data") | ||
|
||
package(default_visibility = ["//visibility:public"]) | ||
|
||
drake_cc_binary( | ||
name = "atlas_run_dynamics", | ||
srcs = [ | ||
"atlas_run_dynamics.cc", | ||
], | ||
add_test_rule = 1, | ||
data = [":models"], | ||
# Smoke test. | ||
test_rule_args = [ | ||
"--simulation_time=0.01", | ||
"--target_realtime_rate=0.0", | ||
], | ||
deps = [ | ||
"//common:find_resource", | ||
"//common:text_logging_gflags", | ||
"//geometry:geometry_visualization", | ||
"//multibody/parsing", | ||
"//multibody/plant:contact_results_to_lcm", | ||
"//systems/analysis:simulator", | ||
"//systems/framework:diagram", | ||
"@gflags", | ||
], | ||
) | ||
|
||
install_data() | ||
|
||
add_lint_tests() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,128 @@ | ||
#include <memory> | ||
|
||
#include <gflags/gflags.h> | ||
|
||
#include "drake/common/find_resource.h" | ||
#include "drake/common/text_logging_gflags.h" | ||
#include "drake/geometry/geometry_visualization.h" | ||
#include "drake/geometry/scene_graph.h" | ||
#include "drake/lcm/drake_lcm.h" | ||
#include "drake/multibody/parsing/parser.h" | ||
#include "drake/multibody/plant/contact_results_to_lcm.h" | ||
#include "drake/systems/analysis/simulator.h" | ||
#include "drake/systems/framework/diagram_builder.h" | ||
|
||
DEFINE_double(target_realtime_rate, 0, | ||
"Desired rate relative to real time (usually between 0 and 1). " | ||
"This is documented in Simulator::set_target_realtime_rate()."); | ||
DEFINE_double(simulation_time, 2.0, "Simulation duration in seconds"); | ||
DEFINE_double( | ||
time_step, 1.0E-3, | ||
"The fixed-time step period (in seconds) of discrete updates for the " | ||
"multibody plant modeled as a discrete system. Strictly positive."); | ||
DEFINE_double(penetration_allowance, 1.0E-3, "Allowable penetration (meters)."); | ||
DEFINE_double(stiction_tolerance, 1.0E-3, | ||
"Allowable drift speed during stiction (m/s)."); | ||
|
||
namespace drake { | ||
namespace examples { | ||
namespace atlas { | ||
namespace { | ||
|
||
using drake::math::RigidTransformd; | ||
using drake::multibody::MultibodyPlant; | ||
using Eigen::Translation3d; | ||
using Eigen::VectorXd; | ||
|
||
int do_main() { | ||
if (FLAGS_time_step <= 0) { | ||
throw std::runtime_error( | ||
"time_step must be a strictly positive number. Only the time-stepping " | ||
"mode is supported for this model."); | ||
} | ||
|
||
// Build a generic multibody plant. | ||
systems::DiagramBuilder<double> builder; | ||
auto pair = AddMultibodyPlantSceneGraph( | ||
&builder, std::make_unique<MultibodyPlant<double>>(FLAGS_time_step)); | ||
MultibodyPlant<double>& plant = pair.plant; | ||
|
||
const std::string full_name = | ||
FindResourceOrThrow("drake/examples/atlas/urdf/atlas_convex_hull.urdf"); | ||
multibody::Parser(&plant).AddModelFromFile(full_name); | ||
|
||
// Add gravity to the model. | ||
plant.AddForceElement<multibody::UniformGravityFieldElement>(); | ||
|
||
// Add model of the ground. | ||
const double static_friction = 1.0; | ||
const Vector4<double> green(0.5, 1.0, 0.5, 1.0); | ||
plant.RegisterVisualGeometry(plant.world_body(), RigidTransformd(), | ||
geometry::HalfSpace(), "GroundVisualGeometry", | ||
green); | ||
// For a time-stepping model only static friction is used. | ||
const multibody::CoulombFriction<double> ground_friction(static_friction, | ||
static_friction); | ||
plant.RegisterCollisionGeometry(plant.world_body(), RigidTransformd(), | ||
geometry::HalfSpace(), | ||
"GroundCollisionGeometry", ground_friction); | ||
|
||
plant.Finalize(); | ||
plant.set_penetration_allowance(FLAGS_penetration_allowance); | ||
|
||
// Set the speed tolerance (m/s) for the underlying Stribeck friction model | ||
// For two points in contact, this is the maximum allowable drift speed at the | ||
// edge of the friction cone, an approximation to true stiction. | ||
plant.set_stiction_tolerance(FLAGS_stiction_tolerance); | ||
|
||
// Sanity check model size. | ||
DRAKE_DEMAND(plant.num_velocities() == 36); | ||
DRAKE_DEMAND(plant.num_positions() == 37); | ||
|
||
// Publish contact results for visualization. | ||
ConnectContactResultsToDrakeVisualizer(&builder, plant); | ||
|
||
geometry::ConnectDrakeVisualizer(&builder, pair.scene_graph); | ||
auto diagram = builder.Build(); | ||
|
||
// Create a context for this system: | ||
std::unique_ptr<systems::Context<double>> diagram_context = | ||
diagram->CreateDefaultContext(); | ||
systems::Context<double>& plant_context = | ||
diagram->GetMutableSubsystemContext(plant, diagram_context.get()); | ||
|
||
const VectorXd tau = VectorXd::Zero(plant.num_actuated_dofs()); | ||
plant.get_actuation_input_port().FixValue(&plant_context, tau); | ||
|
||
// Set the pelvis frame P initial pose. | ||
const drake::multibody::Body<double>& pelvis = plant.GetBodyByName("pelvis"); | ||
const Translation3d X_WP(0.0, 0.0, 0.95); | ||
plant.SetFreeBodyPoseInWorldFrame(&plant_context, pelvis, X_WP); | ||
|
||
systems::Simulator<double> simulator(*diagram, std::move(diagram_context)); | ||
|
||
simulator.set_target_realtime_rate(FLAGS_target_realtime_rate); | ||
simulator.Initialize(); | ||
simulator.StepTo(FLAGS_simulation_time); | ||
|
||
return 0; | ||
} | ||
|
||
} // namespace | ||
} // namespace atlas | ||
} // namespace examples | ||
} // namespace drake | ||
|
||
int main(int argc, char* argv[]) { | ||
gflags::SetUsageMessage( | ||
"\nPassive simulation of the Atlas robot. With the default time step of " | ||
"\n1 ms this simulation typically runs slightly faster than real-time. " | ||
"\nThe time step has an effect on the joint limits stiffnesses, which " | ||
"\nconverge quadratically to the rigid limit as the time step is " | ||
"\ndecreased. Thus, decrease the time step for more accurately resolved " | ||
"\njoint limits. " | ||
"\nLaunch drake-visualizer before running this example."); | ||
gflags::ParseCommandLineFlags(&argc, &argv, true); | ||
drake::logging::HandleSpdlogGflags(); | ||
return drake::examples::atlas::do_main(); | ||
} |