-
Notifications
You must be signed in to change notification settings - Fork 27
/
cassie_kcmpc_trajopt.cc
150 lines (126 loc) · 6.55 KB
/
cassie_kcmpc_trajopt.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
#include <drake/systems/framework/diagram_builder.h>
#include <drake/geometry/scene_graph.h>
#include <drake/multibody/parsing/parser.h>
#include <drake/multibody/plant/multibody_plant.h>
#include <iostream>
#include <drake/systems/primitives/trajectory_source.h>
#include <drake/systems/rendering/multibody_position_to_geometry_pose.h>
#include <drake/systems/analysis/simulator.h>
#include <drake/geometry/drake_visualizer.h>
#include <drake/solvers/solve.h>
#include <drake/common/yaml/yaml_io.h>
#include "common/find_resource.h"
#include "systems/primitives/subvector_pass_through.h"
#include "examples/Cassie/kinematic_centroidal_mpc/cassie_reference_utils.h"
#include "examples/Cassie/kinematic_centroidal_mpc/cassie_kinematic_centroidal_mpc.h"
#include "systems/controllers/kinematic_centroidal_mpc/kinematic_centroidal_gains.h"
#include "systems/controllers/kinematic_centroidal_mpc/kcmpc_reference_generator.h"
using drake::geometry::SceneGraph;
using drake::multibody::MultibodyPlant;
using drake::multibody::Parser;
using drake::geometry::DrakeVisualizer;
void DoMain(int n_knot_points, double duration, double com_height, double stance_width, double vel, double tol){
auto gains = drake::yaml::LoadYamlFile<KinematicCentroidalGains>("examples/Cassie/kinematic_centroidal_mpc/kinematic_centroidal_mpc_gains.yaml");
// Create fix-spring Cassie MBP
drake::systems::DiagramBuilder<double> builder;
SceneGraph<double>& scene_graph = *builder.AddSystem<SceneGraph>();
scene_graph.set_name("scene_graph");
MultibodyPlant<double> plant(0.0);
MultibodyPlant<double> plant_vis(0.0);
Parser parser(&plant);
Parser parser_vis(&plant_vis, &scene_graph);
std::string full_name =
dairlib::FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf");
parser.AddModelFromFile(full_name);
parser_vis.AddModelFromFile(full_name);
plant.Finalize();
plant_vis.Finalize();
// Create MPC and set gains
CassieKinematicCentroidalMPC mpc (plant, n_knot_points, duration/(n_knot_points-1), 0.4);
mpc.SetGains(gains);
// Create gaits
Gait stand ({{0, 1, drake::Vector<bool, 4>(true, true, true, true)}});
stand.SetPeriod(1);
Gait walk({{0, 0.4, drake::Vector<bool, 4>(true, true, false, false)},
{0.4, 0.5, drake::Vector<bool, 4>(true, true, true, true)},
{0.5, 0.9, drake::Vector<bool, 4>(false, false, true, true)},
{0.9, 1.0, drake::Vector<bool, 4>(true, true, true, true)}});
walk.SetPeriod(1.25);
// Create reference
Eigen::VectorXd reference_state = GenerateNominalStand(mpc.Plant(), com_height, stance_width, true);
KcmpcReferenceGenerator generator(plant, reference_state.head(plant.num_positions()), mpc.CreateContactPoints(plant,0));
// Specify knot points
std::vector<double> time_points = {0, 0.5, duration};
std::vector<Eigen::Vector3d> com_vel = {{{0, 0, 0},
{vel, 0, 0},
{vel, 0, 0}}};
std::vector<Gait> gait_samples = {stand, walk, walk};
generator.SetComKnotPoints({time_points, com_vel});
generator.SetGaitSequence({time_points, gait_samples});
generator.Build();
// Add reference and mode sequence
mpc.AddForceTrackingReference(std::make_unique<drake::trajectories::PiecewisePolynomial<double>>(generator.grf_traj_));
mpc.AddGenPosReference(std::make_unique<drake::trajectories::PiecewisePolynomial<double>>(generator.q_trajectory_));
mpc.AddGenVelReference(std::make_unique<drake::trajectories::PiecewisePolynomial<double>>(generator.v_trajectory_));
mpc.AddComReference(std::make_unique<drake::trajectories::PiecewisePolynomial<double>>(generator.com_trajectory_));
mpc.AddContactTrackingReference(std::make_unique<drake::trajectories::PiecewisePolynomial<double>>(generator.contact_traj_));
mpc.AddConstantMomentumReference(Eigen::VectorXd::Zero(6));
mpc.SetModeSequence(generator.contact_sequence_);
// Set initial guess
mpc.AddInitialStateConstraint(reference_state);
mpc.SetRobotStateGuess(generator.q_trajectory_, generator.v_trajectory_);
mpc.SetComPositionGuess(generator.com_trajectory_);
mpc.SetContactGuess(generator.contact_traj_);
mpc.SetForceGuess(generator.grf_traj_);
{
drake::solvers::SolverOptions options;
auto id = drake::solvers::IpoptSolver::id();
options.SetOption(id, "tol", tol);
options.SetOption(id, "dual_inf_tol", tol);
options.SetOption(id, "constr_viol_tol", tol);
options.SetOption(id, "compl_inf_tol", tol);
options.SetOption(id, "max_iter", 200);
options.SetOption(id, "nlp_lower_bound_inf", -1e6);
options.SetOption(id, "nlp_upper_bound_inf", 1e6);
options.SetOption(id, "print_timing_statistics", "yes");
options.SetOption(id, "print_level", 5);
// Set to ignore overall tolerance/dual infeasibility, but terminate when
// primal feasible and objective fails to increase over 5 iterations.
options.SetOption(id, "acceptable_compl_inf_tol", tol);
options.SetOption(id, "acceptable_constr_viol_tol", tol);
options.SetOption(id, "acceptable_obj_change_tol", 1e-3);
options.SetOption(id, "acceptable_tol", 1e2);
options.SetOption(id, "acceptable_iter", 1);
options.SetOption(id, "warm_start_init_point", "no");
mpc.Build(options);
}
double alpha = .2;
mpc.CreateVisualizationCallback(
"examples/Cassie/urdf/cassie_fixed_springs.urdf", alpha);
std::cout << "Solving optimization\n\n";
const auto pp_xtraj = mpc.Solve();
mpc.SaveSolutionToFile(std::string(getenv("HOME")) + "/workspace/dairlib/examples/Cassie/saved_trajectories/kcmpc_solution");
auto traj_source =
builder.AddSystem<drake::systems::TrajectorySource>(pp_xtraj);
auto passthrough = builder.AddSystem<dairlib::systems::SubvectorPassThrough>(
mpc.Plant().num_positions() + mpc.Plant().num_velocities(), 0, mpc.Plant().num_positions());
builder.Connect(traj_source->get_output_port(),
passthrough->get_input_port());
auto to_pose =
builder.AddSystem<drake::systems::rendering::MultibodyPositionToGeometryPose<double>>(plant_vis);
builder.Connect(passthrough->get_output_port(), to_pose->get_input_port());
builder.Connect(
to_pose->get_output_port(),
scene_graph.get_source_pose_port(plant_vis.get_source_id().value()));
DrakeVisualizer<double>::AddToBuilder(&builder, scene_graph);
auto diagram = builder.Build();
while (true) {
drake::systems::Simulator<double> simulator(*diagram);
simulator.set_target_realtime_rate(1.0);
simulator.Initialize();
simulator.AdvanceTo(pp_xtraj.end_time());
}
}
int main(int argc, char* argv[]) {
DoMain(45, 5, 0.8, 0.3, 0.5, 1e-2);
}