-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
render_pose_to_geometry_pose.h
47 lines (36 loc) · 1.4 KB
/
render_pose_to_geometry_pose.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
#pragma once
#include "drake/geometry/frame_kinematics_vector.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/rendering/pose_vector.h"
namespace drake {
namespace systems {
namespace rendering {
/// A direct-feedthrough system that converts the C++ type of poses from
/// rendering::PoseVector<T> on the input to geometry::FramePoseVector<T>
/// on the output.
template <typename T>
class RenderPoseToGeometryPose final : public LeafSystem<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(RenderPoseToGeometryPose)
RenderPoseToGeometryPose(geometry::SourceId, geometry::FrameId);
/// Scalar-converting copy constructor. See @ref system_scalar_conversion.
template <typename U>
explicit RenderPoseToGeometryPose(const RenderPoseToGeometryPose<U>&);
~RenderPoseToGeometryPose() override;
/// Returns the rendering::PoseVector input port.
const InputPort<T>& get_input_port() const {
return LeafSystem<T>::get_input_port(0);
}
/// Returns the geometry::FramePoseVector output port.
const OutputPort<T>& get_output_port() const {
return LeafSystem<T>::get_output_port(0);
}
private:
// Allow different specializations to access each other's private data.
template <typename> friend class RenderPoseToGeometryPose;
const geometry::SourceId source_id_;
const geometry::FrameId frame_id_;
};
} // namespace rendering
} // namespace systems
} // namespace drake