-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
jaco_simulation.cc
166 lines (140 loc) · 6.55 KB
/
jaco_simulation.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
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
/// @file
///
/// This demo sets up a gravity compensated JACO arm within a MultibodyPlant
/// simulation controlled via LCM.
#include <limits>
#include <memory>
#include <gflags/gflags.h>
#include "drake/geometry/drake_visualizer.h"
#include "drake/geometry/scene_graph.h"
#include "drake/manipulation/kinova_jaco/jaco_command_receiver.h"
#include "drake/manipulation/kinova_jaco/jaco_constants.h"
#include "drake/manipulation/kinova_jaco/jaco_status_sender.h"
#include "drake/multibody/parsing/parser.h"
#include "drake/multibody/plant/multibody_plant.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/controllers/inverse_dynamics_controller.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/lcm/lcm_interface_system.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"
#include "drake/systems/primitives/demultiplexer.h"
#include "drake/systems/primitives/multiplexer.h"
#include "drake/visualization/visualization_config_functions.h"
DEFINE_double(simulation_sec, std::numeric_limits<double>::infinity(),
"Number of seconds to simulate.");
DEFINE_double(realtime_rate, 1.0, "");
DEFINE_double(time_step, 3e-3,
"The time step to use for MultibodyPlant model "
"discretization. 0 uses the continuous version of the plant.");
using Eigen::VectorXd;
using drake::geometry::SceneGraph;
using drake::lcm::DrakeLcm;
using drake::manipulation::kinova_jaco::JacoCommandReceiver;
using drake::manipulation::kinova_jaco::JacoStatusSender;
using drake::manipulation::kinova_jaco::kJacoDefaultArmNumJoints;
using drake::manipulation::kinova_jaco::kJacoDefaultArmNumFingers;
using drake::manipulation::kinova_jaco::kJacoLcmStatusPeriod;
using drake::multibody::Body;
using drake::multibody::MultibodyPlant;
using drake::multibody::Parser;
using drake::systems::controllers::InverseDynamicsController;
using drake::systems::Demultiplexer;
using drake::visualization::AddDefaultVisualization;
namespace drake {
namespace examples {
namespace kinova_jaco_arm {
namespace {
const char kUrdfUrl[] =
"package://drake/manipulation/models/jaco_description/urdf/"
"j2s7s300_sphere_collision.urdf";
int DoMain() {
systems::DiagramBuilder<double> builder;
auto [jaco_plant, scene_graph] =
multibody::AddMultibodyPlantSceneGraph(&builder, FLAGS_time_step);
const multibody::ModelInstanceIndex jaco_id =
Parser(&jaco_plant).AddModelsFromUrl(kUrdfUrl).at(0);
jaco_plant.WeldFrames(jaco_plant.world_frame(),
jaco_plant.GetFrameByName("base"));
jaco_plant.Finalize();
// These gains are really just a guess. Velocity limits are not enforced,
// allowing much faster simulated movement than the actual robot.
const int num_positions = jaco_plant.num_positions();
VectorXd kp = VectorXd::Constant(num_positions, 100);
VectorXd kd = 2.0 * kp.array().sqrt();
VectorXd ki = VectorXd::Zero(num_positions);
auto jaco_controller = builder.AddSystem<InverseDynamicsController>(
jaco_plant, kp, ki, kd, false);
builder.Connect(jaco_plant.get_state_output_port(jaco_id),
jaco_controller->get_input_port_estimated_state());
AddDefaultVisualization(&builder);
systems::lcm::LcmInterfaceSystem* lcm =
builder.AddSystem<systems::lcm::LcmInterfaceSystem>();
auto command_sub = builder.AddSystem(
systems::lcm::LcmSubscriberSystem::Make<drake::lcmt_jaco_command>(
"KINOVA_JACO_COMMAND", lcm));
auto command_receiver = builder.AddSystem<JacoCommandReceiver>();
builder.Connect(command_sub->get_output_port(),
command_receiver->get_message_input_port());
auto mux = builder.AddSystem<systems::Multiplexer>(
std::vector<int>({kJacoDefaultArmNumJoints + kJacoDefaultArmNumFingers,
kJacoDefaultArmNumJoints + kJacoDefaultArmNumFingers}));
builder.Connect(command_receiver->get_commanded_position_output_port(),
mux->get_input_port(0));
builder.Connect(command_receiver->get_commanded_velocity_output_port(),
mux->get_input_port(1));
builder.Connect(mux->get_output_port(),
jaco_controller->get_input_port_desired_state());
builder.Connect(jaco_controller->get_output_port_control(),
jaco_plant.get_actuation_input_port(jaco_id));
auto status_pub =
builder.AddSystem(
systems::lcm::LcmPublisherSystem::Make<drake::lcmt_jaco_status>(
"KINOVA_JACO_STATUS", lcm, kJacoLcmStatusPeriod));
// TODO(sammy-tri) populate joint torque (and external torques). External
// torques might want to wait until after #12631 is fixed or it could slow
// down the simulation significantly.
auto status_sender = builder.AddSystem<JacoStatusSender>();
auto demux = builder.AddSystem<systems::Demultiplexer>(
std::vector<int>({kJacoDefaultArmNumJoints + kJacoDefaultArmNumFingers,
kJacoDefaultArmNumJoints + kJacoDefaultArmNumFingers}));
builder.Connect(jaco_plant.get_state_output_port(jaco_id),
demux->get_input_port());
builder.Connect(demux->get_output_port(0),
status_sender->get_position_input_port());
builder.Connect(demux->get_output_port(0),
command_receiver->get_position_measured_input_port());
builder.Connect(demux->get_output_port(1),
status_sender->get_velocity_input_port());
builder.Connect(status_sender->get_output_port(),
status_pub->get_input_port());
std::unique_ptr<systems::Diagram<double>> diagram = builder.Build();
systems::Simulator<double> simulator(*diagram);
systems::Context<double>& root_context = simulator.get_mutable_context();
// Set the initial position to something similar to where the jaco moves to
// when starting teleop.
VectorXd initial_position = VectorXd::Zero(num_positions);
initial_position(0) = 1.80;
initial_position(1) = 3.44;
initial_position(2) = 3.14;
initial_position(3) = 0.76;
initial_position(4) = 4.63;
initial_position(5) = 4.49;
initial_position(6) = 5.03;
jaco_plant.SetPositions(
&diagram->GetMutableSubsystemContext(jaco_plant, &root_context),
initial_position);
simulator.Initialize();
simulator.set_publish_every_time_step(false);
simulator.set_target_realtime_rate(FLAGS_realtime_rate);
simulator.AdvanceTo(FLAGS_simulation_sec);
return 0;
}
} // namespace
} // namespace kinova_jaco_arm
} // namespace examples
} // namespace drake
int main(int argc, char* argv[]) {
gflags::ParseCommandLineFlags(&argc, &argv, true);
return drake::examples::kinova_jaco_arm::DoMain();
}