Drake
drake_visualizer.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <memory>
4 #include <vector>
5 
9 #include "drake/lcmt_viewer_draw.hpp"
10 #include "drake/lcmt_viewer_load_robot.hpp"
16 
17 namespace drake {
18 namespace systems {
19 
20 /**
21  * This is a Drake System block that takes a RigidBodyTree and publishes LCM
22  * messages that are intended for drake-visualizer. It does this in two
23  * phases: initialization and run-time. This system holds a DiscreteState in
24  * its context that identifies whether the initialization phase has been
25  * completed. It is initialized to false in SetDefaultState(). The
26  * initialization phase is performed in DoCalcDiscreteVariableUpdates(), which
27  * is scheduled by DoCalcNextUpdateTime(). This class is intended to be used
28  * only in the System framework with proper event handling. If this is not the
29  * use case, users are encouraged to send the LCM messages directly through LCM.
30  * ViewerDrawTranslator and multibody::CreateLoadRobotMessage() are useful for
31  * generating the appropriate LCM messages.
32  *
33  * During initialization, this system block analyzes the RigidBodyTree and tells
34  * Drake Visualizer what it will be visualizing. For example, these include the
35  * number of rigid bodies, their dimensions, and colors. The LCM message used
36  * during this phase is called `lcmt_viewer_load_robot` and the channel name is
37  * "DRAKE_VIEWER_LOAD_ROBOT".
38  *
39  * During run-time, this system block takes the current state of the model and
40  * tells drake-visualizer how to visualize the model. For example, this includes
41  * the position and orientation of each rigid body. The LCM messages used during
42  * this phase is `lcmt_viewer_draw` and the channel name is
43  * "DRAKE_VIEWER_DRAW".
44  *
45  * The visualizer has an option that causes it to save the state it dispatches
46  * for drawing and allows replay of that cached data at wall clock time --
47  * i.e., one second of simulation is played back for every second in the real
48  * world. The playback *rate* is currently capped at 60 Hz. This is useful
49  * for immediate review of simulations which evaluate at time rates radically
50  * out of scale with wall clock time, enabling intuitive understanding of the
51  * simulation results. See ReplayCachedSimulation().
52  *
53  * @ingroup rigid_body_systems
54  */
55 class DrakeVisualizer : public LeafSystem<double> {
56  public:
58 
59  /**
60  * A constructor that prepares for the transmission of `lcmt_viewer_draw` and
61  * `lcmt_viewer_load_robot` messages, but does not actually publish anything.
62  * LCM message publications occur each time DrakeVisualizer::Publish() is
63  * called.
64  *
65  * @param[in] tree A reference to the rigid body tree that should be
66  * visualized by Drake Visualizer. This reference must remain valid for the
67  * duration of this object.
68  *
69  * @param[in] lcm A pointer to the object through which LCM messages can be
70  * published. This pointer must remain valid for the duration of this object.
71  *
72  * @param[in] enable_playback If true, the visualizer will cache the
73  * input data for playback and ReplayCachedSimulation() will replay that
74  * cache data.
75  */
78  bool enable_playback = false);
79 
80  /**
81  * Sets the publishing period of this system. See
82  * LeafSystem::DeclarePublishPeriodSec() for details about the semantics of
83  * parameter `period`.
84  */
85  void set_publish_period(double period);
86 
87  // TODO(SeanCurtis-TRI): Optional features:
88  // 1. Specify number of loops (<= 0 --> infinite looping)
89  // 2. Specify range of playback [start, end] for cached data from times
90  // in the range [0, T], such that start < end, start >= 0 and
91  // end <= T. (Although, putting end > T *is* valid, it would
92  // manifest as a *pause* at the end of the playback before finishing.
93  // 3. Optionally force the replay to emit the messages to load the
94  // geometry again.
95  // 4. Specify playback rate.
96  // 5. Add a wall-clock scale factor; e.g., play faster than real time,
97  // slower than real time, etc.
98  /**
99  * Causes the visualizer to playback its cached data at real time. If it has
100  * not been configured to record/playback, a warning message will be written
101  * to the log, but otherwise, no work will be done.
102  */
103  void ReplayCachedSimulation() const;
104 
105  /**
106  * Plays back (at real time) a trajectory representing the input signal.
107  */
108  void PlaybackTrajectory(
109  const trajectories::PiecewisePolynomial<double>& input_trajectory) const;
110 
111  /**
112  * Publishes a lcmt_viewer_load_robot message containing a description
113  * of what should be visualized. The message is intended to be received by
114  * drake-visualizer. This method is automatically invoked when the
115  * DrakeVisualizer instance is analyzed by a systems::Simulator.
116  */
117  void PublishLoadRobot() const;
118 
119  private:
120  // TODO(siyuan): Split DoPublish into individual callbacks for different
121  // events. Since the desired behaviors for different triggers are exclusive.
122 
123  // If @p events has only 1 kInitialization trigger typed event, calls
124  // PublishLoadRobot. Otherwise it publishes a draw message.
125  void DoPublish(const systems::Context<double>& context,
126  const std::vector<const PublishEvent<double>*>& events)
127  const override;
128 
129  // A pointer to the LCM subsystem. It is through this object that LCM messages
130  // are published.
131  drake::lcm::DrakeLcmInterface* const lcm_;
132 
133  // The LCM load message to send to the Drake Visualizer.
134  const lcmt_viewer_load_robot load_message_;
135 
136  // The translator that converts from the RigidBodyTree's generalized state
137  // vector to a lcmt_viewer_draw message.
138  const ViewerDrawTranslator draw_message_translator_;
139 
140  // The (optional) log used for recording and playback.
141  std::unique_ptr<SignalLog<double>> log_{nullptr};
142 
143  // The RigidBodyTree with which the poses of each RigidBody can be
144  // determined given the state vector of the RigidBodyTree.
145  const RigidBodyTree<double>& tree_;
146 };
147 
148 } // namespace systems
149 } // namespace drake
Definition: automotive_demo.cc:90
This is a Drake System block that takes a RigidBodyTree and publishes LCM messages that are intended ...
Definition: drake_visualizer.h:55
void PlaybackTrajectory(const trajectories::PiecewisePolynomial< double > &input_trajectory) const
Plays back (at real time) a trajectory representing the input signal.
Definition: drake_visualizer.cc:80
void ReplayCachedSimulation() const
Causes the visualizer to playback its cached data at real time.
Definition: drake_visualizer.cc:41
std::vector< double > vector
Definition: translator_test.cc:20
A pure virtual interface that enables LCM to be mocked.
Definition: drake_lcm_interface.h:22
Specializes LcmAndVectorBaseTranslator to handle LCM messages of type drake::lcmt_viewer_draw.
Definition: viewer_draw_translator.h:21
A superclass template that extends System with some convenience utilities that are not applicable to ...
Definition: leaf_system.h:85
void PublishLoadRobot() const
Publishes a lcmt_viewer_load_robot message containing a description of what should be visualized...
Definition: drake_visualizer.cc:152
void set_publish_period(double period)
Sets the publishing period of this system.
Definition: drake_visualizer.cc:37
This class represents a publish event.
Definition: event.h:332
#define DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Classname)
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN deletes the special member functions for copy-construction, copy-assignment, move-construction, and move-assignment.
Definition: drake_copyable.h:33
DrakeVisualizer(const DrakeVisualizer &)=delete
Provides careful macros to selectively enable or disable the special member functions for copy-constr...