forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
iiwa_status_receiver.h
67 lines (58 loc) · 2.19 KB
/
iiwa_status_receiver.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
#pragma once
#include <vector>
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/lcmt_iiwa_status.hpp"
#include "drake/manipulation/kuka_iiwa/iiwa_constants.h"
#include "drake/systems/framework/leaf_system.h"
namespace drake {
namespace manipulation {
namespace kuka_iiwa {
/// Handles lcmt_iiwa_status messages from a LcmSubscriberSystem.
///
/// Note that this system does not actually subscribe to an LCM channel. To
/// receive the message, the input of this system should be connected to a
/// systems::lcm::LcmSubscriberSystem::Make<lcmt_iiwa_status>().
///
/// This system has one abstract-valued input port of type lcmt_iiwa_status.
///
/// This system has many vector-valued output ports, each of which has exactly
/// num_joints elements. The ports will output zeros until an input message is
/// received.
//
/// @system
/// name: IiwaStatusReceiver
/// input_ports:
/// - lcmt_iiwa_status
/// output_ports:
/// - position_commanded
/// - position_measured
/// - velocity_estimated
/// - torque_commanded
/// - torque_measured
/// - torque_external
/// @endsystem
///
/// @see `lcmt_iiwa_status.lcm` for additional documentation.
class IiwaStatusReceiver : public systems::LeafSystem<double> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(IiwaStatusReceiver)
explicit IiwaStatusReceiver(int num_joints = kIiwaArmNumJoints);
/// @name Named accessors for this System's input and output ports.
//@{
const systems::OutputPort<double>& get_position_commanded_output_port() const;
const systems::OutputPort<double>& get_position_measured_output_port() const;
const systems::OutputPort<double>& get_velocity_estimated_output_port() const;
const systems::OutputPort<double>& get_torque_commanded_output_port() const;
const systems::OutputPort<double>& get_torque_measured_output_port() const;
const systems::OutputPort<double>& get_torque_external_output_port() const;
//@}
private:
template <std::vector<double> drake::lcmt_iiwa_status::*>
void CalcLcmOutput(const systems::Context<double>&,
systems::BasicVector<double>*) const;
const int num_joints_;
};
} // namespace kuka_iiwa
} // namespace manipulation
} // namespace drake