-
Notifications
You must be signed in to change notification settings - Fork 0
/
automotive_simulator.h
376 lines (325 loc) · 15.1 KB
/
automotive_simulator.h
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
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
#pragma once
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "drake/automotive/car_vis_applicator.h"
#include "drake/automotive/curve2.h"
#include "drake/automotive/gen/maliput_railcar_state.h"
#include "drake/automotive/idm_controller.h"
///////////////////////////////changes///////////////////////////////////////
#include "drake/automotive/idm_controller2.h"
///////////////////////////////changes///////////////////////////////////////
#include "drake/automotive/lane_direction.h"
#include "drake/automotive/maliput/api/road_geometry.h"
#include "drake/automotive/maliput_railcar.h"
#include "drake/automotive/mobil_planner.h"
///////////////////////////////changes///////////////////////////////////////
#include "drake/automotive/mobil_planner2.h"
///////////////////////////////changes end///////////////////////////////////
#include "drake/automotive/mobil_planner3.h"
///////////////////////////////changes end///////////////////////////////////
#include "drake/automotive/pure_pursuit_controller.h"
#include "drake/automotive/simple_car.h"
#include "drake/automotive/simple_car_to_euler_floating_joint.h"
#include "drake/automotive/trajectory_car.h"
#include "drake/common/drake_copyable.h"
#include "drake/lcm/drake_lcm_interface.h"
#include "drake/lcmt_viewer_load_robot.hpp"
#include "drake/multibody/rigid_body_tree.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/diagram.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/system_port_descriptor.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
#include "drake/systems/rendering/pose_aggregator.h"
#include "drake/systems/rendering/pose_bundle.h"
#include "drake/systems/rendering/pose_bundle_to_draw_message.h"
namespace drake {
namespace automotive {
/// AutomotiveSimulator is a helper class for constructing and running
/// automotive-related simulations.
///
/// @tparam T must be a valid Eigen ScalarType.
///
/// Instantiated templates for the following ScalarTypes are provided:
/// - double
///
/// They are already available to link against in the containing library.
template <typename T>
class AutomotiveSimulator {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(AutomotiveSimulator)
/// A constructor that configures this object to use DrakeLcm, which
/// encapsulates a _real_ LCM instance.
AutomotiveSimulator();
explicit AutomotiveSimulator(std::unique_ptr<lcm::DrakeLcmInterface> lcm);
~AutomotiveSimulator();
/// Returns the LCM object used by this AutomotiveSimulator.
lcm::DrakeLcmInterface* get_lcm();
/// Returns the DiagramBuilder.
/// @pre Start() has NOT been called.
systems::DiagramBuilder<T>* get_builder();
/// Adds a SimpleCar to this simulation visualized as a Toyota Prius. This
/// includes its DrivingCommand LCM input and EulerFloatingJoint output.
///
/// @pre Start() has NOT been called.
///
/// @param name The car's name, which must be unique among all cars. Otherwise
/// a std::runtime_error will be thrown.
///
/// @param channel_name The SimpleCar will subscribe to an LCM channel of
/// this name to receive commands. It must be non-empty.
///
/// @param initial_state The SimpleCar's initial state.
///
/// @return The ID of the car that was just added to the simulation.
int AddPriusSimpleCar(
const std::string& name, const std::string& channel_name,
const SimpleCarState<T>& initial_state = SimpleCarState<T>());
/// Adds a SimpleCar to this simulation controlled by a MOBIL planner coupled
/// with a PurePursuitController to perform lateral control of the vehicle,
/// along with an IDM longitudinal controller. The car is visualized as a
/// Toyota Prius.
///
/// @pre Start() has NOT been called.
///
/// @pre SetRoadGeometry() was called. Otherwise, a std::runtime_error will be
/// thrown.
///
/// @param name The car's name, which must be unique among all cars.
/// Otherwise a std::runtime_error will be thrown.
///
/// @param initial_with_s Initial travel direction in the lane. (See
/// MobilPlanner documentation.)
///
/// @param initial_state The SimpleCar's initial state.
///
/// @return The ID of the car that was just added to the simulation.
int AddMobilControlledSimpleCar(
const std::string& name, bool initial_with_s,
const SimpleCarState<T>& initial_state = SimpleCarState<T>());
///////////////////////////////changes///////////////////////////////////////
int AddMobil2ControlledSimpleCar(
const std::string& name, bool initial_with_s,
const SimpleCarState<T>& initial_state = SimpleCarState<T>());
///////////////////////////////changes end///////////////////////////////////
///////////////////////////////changes///////////////////////////////////////
int AddMobil3ControlledSimpleCar(
const std::string& name, bool initial_with_s,
const SimpleCarState<T>& initial_state = SimpleCarState<T>());
///////////////////////////////changes end///////////////////////////////////
/// Adds a TrajectoryCar to this simulation visualized as a Toyota Prius. This
/// includes its EulerFloatingJoint output.
///
/// @pre Start() has NOT been called.
///
/// @param name The car's name, which must be unique among all cars. Otherwise
/// a std::runtime_error will be thrown.
///
/// @param curve See documentation of TrajectoryCar::TrajectoryCar.
///
/// @param speed See documentation of TrajectoryCar::TrajectoryCar.
///
/// @param start_time See documentation of TrajectoryCar::TrajectoryCar.
///
/// @return The ID of the car that was just added to the simulation.
int AddPriusTrajectoryCar(const std::string& name,
const Curve2<double>& curve, double speed,
double start_time);
/// Adds a MaliputRailcar to this simulation visualized as a Toyota Prius.
///
/// @pre Start() has NOT been called.
///
/// @pre SetRoadGeometry() was called. Otherwise, a std::runtime_error will be
/// thrown.
///
/// @param name The car's name, which must be unique among all cars. Otherwise
/// a std::runtime_error will be thrown.
///
/// @param initial_lane_direction The MaliputRailcar's initial lane and
/// direction on the lane. The lane in this parameter must be part of the
/// maliput::api::RoadGeometry that is added via SetRoadGeometry(). Otherwise
/// a std::runtime_error will be thrown.
///
/// @param params The MaliputRailcar's parameters. This is an optional
/// parameter. Defaults are used if this parameter is not provided.
///
/// @param initial_state The MaliputRailcar's initial state. This is an
/// optional parameter. Defaults are used if this parameter is not provided.
///
/// @return The ID of the car that was just added to the simulation.
int AddPriusMaliputRailcar(
const std::string& name, const LaneDirection& initial_lane_direction,
const MaliputRailcarParams<T>& params = MaliputRailcarParams<T>(),
const MaliputRailcarState<T>& initial_state = MaliputRailcarState<T>());
/// Adds a MaliputRailcar to this simulation visualized as a Toyota Prius that
/// is controlled via an IdmController.
///
/// @pre Start() has NOT been called.
///
/// @pre SetRoadGeometry() was called. Otherwise, a std::runtime_error will be
/// thrown.
///
/// @param name The car's name, which must be unique among all cars. Otherwise
/// a std::runtime_error will be thrown.
///
/// @param initial_lane_direction The MaliputRailcar's initial lane and
/// direction on the lane. The lane in this parameter must be part of the
/// maliput::api::RoadGeometry that is added via SetRoadGeometry(). Otherwise
/// a std::runtime_error will be thrown.
///
/// @param params The MaliputRailcar's parameters. This is an optional
/// parameter. Defaults are used if this parameter is not provided.
///
/// @param initial_state The MaliputRailcar's initial state. This is an
/// optional parameter. Defaults are used if this parameter is not provided.
///
/// @return The ID of the car that was just added to the simulation.
int AddIdmControlledPriusMaliputRailcar(
const std::string& name, const LaneDirection& initial_lane_direction,
const MaliputRailcarParams<T>& params = MaliputRailcarParams<T>(),
const MaliputRailcarState<T>& initial_state = MaliputRailcarState<T>());
/// Sets the acceleration command of a particular MaliputRailcar.
///
/// @param id The ID of the MaliputRailcar. This is the ID that was returned
/// by the method that added the MaliputRailcar to the simulation. If no
/// MaliputRailcar with such an ID exists, a std::runtime_error is thrown.
///
/// @param acceleration The acceleration command to issue to the
/// MaliputRailcar.
///
/// @pre Start() has been called.
void SetMaliputRailcarAccelerationCommand(int id, double acceleration);
/// Sets the RoadGeometry for this simulation.
///
/// @pre Start() has NOT been called.
const maliput::api::RoadGeometry* SetRoadGeometry(
std::unique_ptr<const maliput::api::RoadGeometry> road);
/// Finds and returns a pointer to a lane with the specified name. This method
/// throws a std::runtime_error if no such lane exists.
///
/// @pre SetRoadGeometry() was called.
///
const maliput::api::Lane* FindLane(const std::string& name) const;
/// Returns the System whose name matches @p name. Throws an exception if no
/// such system has been added, or multiple such systems have been added.
//
/// This is the builder variant of the method. It can only be used prior to
/// Start() being called.
///
/// @pre Start() has NOT been called.
systems::System<T>& GetBuilderSystemByName(std::string name);
/// Returns the System whose name matches @p name. Throws an exception if no
/// such system has been added, or multiple such systems have been added.
///
/// This is the diagram variant of the method, which can only be used after
/// Start() is called.
///
/// @pre Start() has been called.
const systems::System<T>& GetDiagramSystemByName(std::string name) const;
/// Builds the Diagram. No further changes to the diagram may occur after
/// this has been called.
///
/// @pre Build() has NOT been called.
void Build();
/// Returns the System containing the entire AutomotiveSimulator diagram.
///
/// @pre Build() has been called.
const systems::System<T>& GetDiagram() const {
DRAKE_DEMAND(diagram_ != nullptr);
return *diagram_;
}
/// Calls Build() on the diagram (if it has not been build already) and
/// initializes the Simulator. No further changes to the diagram may occur
/// after this has been called.
///
/// @pre Start() has NOT been called.
///
/// @param target_realtime_rate This value is passed to
/// systems::Simulator::set_target_realtime_rate().
//
// TODO(jwnimmer-tri) Perhaps our class should be AutomotiveSimulatorBuilder?
// Port a few more demo programs, then decide what looks best.
void Start(double target_realtime_rate = 0.0);
/// Returns whether the automotive simulator has started.
bool has_started() const { return simulator_ != nullptr; }
/// Advances simulated time by the given @p time_step increment in seconds.
void StepBy(const T& time_step);
/// Returns the current poses of all vehicles in the simulation.
///
/// @pre Start() has been called.
systems::rendering::PoseBundle<T> GetCurrentPoses() const;
private:
int allocate_vehicle_number();
// Verifies that the provided `name` of a car is unique among all cars that
// have been added to the `AutomotiveSimulator`. Throws a std::runtime_error
// if it is not unique meaning a car of the same name was already added.
void CheckNameUniqueness(const std::string& name);
// Connects the provided pose and velocity output ports of a vehicle model to
// the PoseAggregator and adds a PriusVis for visualizing the vehicle.
void ConnectCarOutputsAndPriusVis(int id,
const systems::OutputPortDescriptor<T>& pose_output,
const systems::OutputPortDescriptor<T>& velocity_output);
// Adds an LCM publisher for the given @p system.
// @pre Start() has NOT been called.
void AddPublisher(const MaliputRailcar<T>& system, int vehicle_number);
// Adds an LCM publisher for the given @p system.
// @pre Start() has NOT been called.
void AddPublisher(const SimpleCar<T>& system, int vehicle_number);
// Adds an LCM publisher for the given @p system.
// @pre Start() has NOT been called.
void AddPublisher(const TrajectoryCar<T>& system, int vehicle_number);
// Adds an LCM publisher for the given @p system.
// @pre Start() has NOT been called.
void AddPublisher(const SimpleCarToEulerFloatingJoint<T>& system,
int vehicle_number);
// Generates the URDF model of the road network and loads it into the
// `RigidBodyTree`. Member variable `road_` must be set prior to calling this
// method.
void GenerateAndLoadRoadNetworkUrdf();
// Creates a lcmt_load_robot message containing all visual elements in the
// simulation and sends it to the drake-visualizer.
void TransmitLoadMessage();
void SendLoadRobotMessage(const lcmt_viewer_load_robot& message);
void InitializeSimpleCars();
void InitializeMaliputRailcars();
// For both building and simulation.
std::unique_ptr<lcm::DrakeLcmInterface> lcm_{};
std::unique_ptr<const maliput::api::RoadGeometry> road_{};
// === Start for building. ===
std::unique_ptr<RigidBodyTree<T>> tree_{std::make_unique<RigidBodyTree<T>>()};
std::unique_ptr<systems::DiagramBuilder<T>> builder_{
std::make_unique<systems::DiagramBuilder<T>>()};
// Holds the desired initial states of each SimpleCar. It is used to
// initialize the simulation's diagram's state.
std::map<const SimpleCar<T>*, SimpleCarState<T>> simple_car_initial_states_;
// Holds the desired initial states of each MaliputRailcar. It is used to
// initialize the simulation's diagram's state.
std::map<const MaliputRailcar<T>*,
std::pair<MaliputRailcarParams<T>, MaliputRailcarState<T>>>
railcar_configs_;
// The output port of the Diagram that contains pose bundle information.
int pose_bundle_output_port_{};
// === End for building. ===
// Adds the PoseAggregator.
systems::rendering::PoseAggregator<T>* aggregator_{};
// Takes the poses of the vehicles and outputs the poses of the visual
// elements that make up the visualization of the vehicles. For a system-level
// architecture diagram, see #5541.
CarVisApplicator<T>* car_vis_applicator_{};
// Takes the output of car_vis_applicator_ and creates an lcmt_viewer_draw
// message containing the latest poses of the visual elements.
systems::rendering::PoseBundleToDrawMessage* bundle_to_draw_{};
// Takes the output of bundle_to_draw_ and passes it to lcm_ for publishing.
systems::lcm::LcmPublisherSystem* lcm_publisher_{};
int next_vehicle_number_{0};
// Maps a vehicle id to a pointer to the system that implements the vehicle.
std::map<int, systems::System<T>*> vehicles_;
// For simulation.
std::unique_ptr<systems::Diagram<T>> diagram_{};
std::unique_ptr<systems::Simulator<T>> simulator_{};
};
} // namespace automotive
} // namespace drake