Line |
Branch |
Exec |
Source |
1 |
|
|
// Copyright (c) 2018, Joseph Mirabel |
2 |
|
|
// Authors: Joseph Mirabel (joseph.mirabel@laas.fr) |
3 |
|
|
|
4 |
|
|
#ifndef __SOT_EVENT_H__ |
5 |
|
|
#define __SOT_EVENT_H__ |
6 |
|
|
|
7 |
|
|
#include <dynamic-graph/command-bind.h> |
8 |
|
|
#include <dynamic-graph/command-getter.h> |
9 |
|
|
#include <dynamic-graph/command-setter.h> |
10 |
|
|
#include <dynamic-graph/entity.h> |
11 |
|
|
#include <dynamic-graph/pool.h> |
12 |
|
|
#include <dynamic-graph/signal-ptr.h> |
13 |
|
|
#include <dynamic-graph/signal-time-dependent.h> |
14 |
|
|
#include <dynamic-graph/signal.h> |
15 |
|
|
|
16 |
|
|
#include <sot/core/config.hh> |
17 |
|
|
|
18 |
|
|
namespace dynamicgraph { |
19 |
|
|
namespace sot { |
20 |
|
|
/// Event |
21 |
|
|
/// |
22 |
|
|
/// This entity detects changes in value of an input boolean signal |
23 |
|
|
/// |
24 |
|
|
/// Input signal is |
25 |
|
|
/// - condition (boolean), |
26 |
|
|
/// Output signal is |
27 |
|
|
/// - check |
28 |
|
|
/// output value is true if value of input signal changes with respect to the |
29 |
|
|
/// evaluation. |
30 |
|
|
/// |
31 |
|
|
/// Method addSignal stores signals that are recomputed each time the output |
32 |
|
|
/// signal is recomputed and the value is true. One typical use case of this |
33 |
|
|
/// feature consists in plugging the output signal to a ROS topic using |
34 |
|
|
/// dynamicgraph::RosPublish entity (see dynamic_graph_bridge) and to call |
35 |
|
|
/// addSignal with the trigger signal of the RosPublish entity as the input. |
36 |
|
|
/// Thus each time the output signal changes value, the new value is published |
37 |
|
|
/// to the ROS topic. |
38 |
|
|
/// |
39 |
|
|
/// If command setOnlyUp is called with true as input, signals are recomputed |
40 |
|
|
/// only if the output value switches from false to true. |
41 |
|
|
|
42 |
|
|
class SOT_CORE_DLLAPI Event : public dynamicgraph::Entity { |
43 |
|
✗ |
DYNAMIC_GRAPH_ENTITY_DECL(); |
44 |
|
|
|
45 |
|
✗ |
Event(const std::string &name) |
46 |
|
✗ |
: Entity(name), |
47 |
|
✗ |
checkSOUT("Event(" + name + ")::output(bool)::check"), |
48 |
|
✗ |
conditionSIN(NULL, "Event(" + name + ")::input(bool)::condition"), |
49 |
|
✗ |
lastVal_(2), // lastVal_ should be different true and false. |
50 |
|
✗ |
timeSinceUp_(0), |
51 |
|
✗ |
repeatAfterNIterations_(0) { |
52 |
|
✗ |
checkSOUT.setFunction(boost::bind(&Event::check, this, _1, _2)); |
53 |
|
✗ |
signalRegistration(conditionSIN); |
54 |
|
✗ |
signalRegistration(checkSOUT); |
55 |
|
|
|
56 |
|
|
using command::makeCommandVoid1; |
57 |
|
|
std::string docstring = |
58 |
|
|
"\n" |
59 |
|
✗ |
" Add a signal\n"; |
60 |
|
✗ |
addCommand("addSignal", |
61 |
|
✗ |
makeCommandVoid1(*this, &Event::addSignal, docstring)); |
62 |
|
|
|
63 |
|
|
docstring = |
64 |
|
|
"\n" |
65 |
|
✗ |
" Get list of signals\n"; |
66 |
|
✗ |
addCommand("list", new command::Getter<Event, std::string>( |
67 |
|
✗ |
*this, &Event::getSignalsByName, docstring)); |
68 |
|
|
|
69 |
|
|
docstring = |
70 |
|
|
"\n" |
71 |
|
|
" Repease event if input signal remains True for a while\n" |
72 |
|
|
" Input: number of iterations before repeating output\n." |
73 |
|
✗ |
" 0 for no repetition"; |
74 |
|
✗ |
addCommand("repeat", new command::Setter<Event, int>(*this, &Event::repeat, |
75 |
|
✗ |
docstring)); |
76 |
|
|
} |
77 |
|
|
|
78 |
|
✗ |
~Event() {} |
79 |
|
|
|
80 |
|
|
/// Header documentation of the python class |
81 |
|
✗ |
virtual std::string getDocString() const { |
82 |
|
|
return "Send an event when the input changes\n\n" |
83 |
|
|
" The signal triggered is called whenever the condition is " |
84 |
|
✗ |
"satisfied.\n"; |
85 |
|
|
} |
86 |
|
|
|
87 |
|
✗ |
void addSignal(const std::string &signal) { |
88 |
|
✗ |
std::istringstream iss(signal); |
89 |
|
✗ |
triggers.push_back(&PoolStorage::getInstance()->getSignal(iss)); |
90 |
|
|
} |
91 |
|
|
|
92 |
|
|
// Returns the Python string representation of the list of signal names. |
93 |
|
✗ |
std::string getSignalsByName() const { |
94 |
|
✗ |
std::ostringstream oss; |
95 |
|
✗ |
oss << "("; |
96 |
|
✗ |
for (Triggers_t::const_iterator _sig = triggers.begin(); |
97 |
|
✗ |
_sig != triggers.end(); ++_sig) |
98 |
|
✗ |
oss << '\'' << (*_sig)->getName() << "\', "; |
99 |
|
✗ |
oss << ")"; |
100 |
|
✗ |
return oss.str(); |
101 |
|
|
} |
102 |
|
|
|
103 |
|
✗ |
void repeat(const int &nbIterations) { |
104 |
|
✗ |
repeatAfterNIterations_ = nbIterations; |
105 |
|
|
} |
106 |
|
|
|
107 |
|
|
private: |
108 |
|
|
typedef SignalBase<int> *Trigger_t; |
109 |
|
|
typedef std::vector<Trigger_t> Triggers_t; |
110 |
|
|
|
111 |
|
|
bool &check(bool &ret, const int &time); |
112 |
|
|
|
113 |
|
|
Signal<bool, int> checkSOUT; |
114 |
|
|
|
115 |
|
|
Triggers_t triggers; |
116 |
|
|
SignalPtr<bool, int> conditionSIN; |
117 |
|
|
|
118 |
|
|
bool lastVal_; |
119 |
|
|
int timeSinceUp_, repeatAfterNIterations_; |
120 |
|
|
}; |
121 |
|
|
} // namespace sot |
122 |
|
|
} // namespace dynamicgraph |
123 |
|
|
#endif // __SOT_EVENT_H__ |
124 |
|
|
|