AuboCaps  0.4.1
script_writer.h
Go to the documentation of this file.
1 #ifndef AUBO_SCOPE_SCRIPT_WRITER_H
2 #define AUBO_SCOPE_SCRIPT_WRITER_H
3 
4 #include <vector>
5 #include <string>
7 
8 namespace arcs {
9 namespace aubo_scope {
10 ARCS_CLASS_FORWARD(ScriptWriter);
11 
12 /**
13  * This interface provides support for generating Script code.
14  */
16 {
17 public:
20  virtual ~ScriptWriter();
21 
22  void setLable(int lineno, const std::string &comment);
23 
24  /**
25  * Adds a single line of script code using auto-indentation.
26  *
27  * @param script_line single line of script code to append.
28  */
29  void appendLine(const std::string &script_line);
30  void appendVectorDouble(const std::vector<double> &value);
31 
32  /**
33  * Adds script code appending the script code as is without using
34  * auto-indentation.
35  *
36  * @param script script code to append.
37  */
38  void appendRaw(const std::string &script);
39 
40  /**
41  * Generate a string with the full script code.
42  *
43  * @return the resulting script as a string.
44  */
45  std::string generateScript();
46 
47  /**
48  * <p>
49  * Use this method when generating script code for a node that has children
50  * nodes.globalVariable
51  * </p>
52  *
53  * A simple example:
54  * <pre>
55  * {@code
56  * writer.ifCondition(expression)
57  * writer.writeChildren() // let children nodes generate code.
58  * writer.end()
59  * @endcode}
60  * </pre>
61  *
62  * In most cases you prglobalVariableobably only want to call {@link
63  * ScriptWriter#writeChildren()} once, but it is possible to call it
64  * multiple times and thus have children nodes generate their code multiple
65  * times.
66  */
67  void writeChildren();
68 
69  /**
70  * <p>Variable assignment.
71  * Assigns the variable without a local or global qualifier.
72  * See the Script Manual for the scoping rules.</p>
73  * @param variableName name of the variable, not null.
74  * @param expression expression that is assigned to the variable, not null.
75  */
76  void assign(const std::string &variableName, const std::string &expression);
77 
78  /**
79  * <p>Variable assignment.</p>
80  * @param variable the variable to assign an expression to, not null.
81  * @param expression expression that is assigned to the variable, not null.
82  */
83  void assign(VariablePtr variable, const std::string &expression);
84 
85  /**
86  * Add 1 to the variable value.
87  *
88  * @param variable the variable to increment. Not <code>null</code>.
89  */
90  void incrementVariable(const std::string &variable_name);
91 
92  /**
93  * Add a note.
94  *
95  * @param expression the note expression.
96  */
97  void note(const std::string &expression);
98 
99  /**
100  * Sleep for a number of seconds.
101  *
102  * @param seconds amount of time to sleep in seconds.
103  */
104  void sleep(double seconds);
105 
106  /**
107  * Uses up the remaining "physical" time a thread has in the current frame.
108  */
109  void sync();
110 
111  /**
112  *
113  * @param name Define a function of name name.
114  */
115  void defineFunction(const std::string &func_name);
116  void anonyFunction(const std::string &func_name);
117 
118  /**
119  * Return from method.
120  */
121  void returnMethod();
122 
123  /**
124  * Insert an end.
125  */
126  void end();
127 
128  /**
129  * Insert an empty line.
130  */
131  void lineFeed();
132 
133  /**
134  * <p>
135  * Sets the mass and Center of Gravity (CoG) of the payload.
136  * </p>
137  *
138  * This function must be called, when the payload weight or weigh
139  * distribution changes significantly, i.e when the robot arm picks up or
140  * puts down a heavy workpiece.
141  *
142  * @param payloadMass in kilograms
143  * @param centerOfGravityX displacement from the tool-mount in meters.
144  * @param centerOfGravityY displacement from the tool-mount in meters.
145  * @param centerOfGravityZ displacement from the tool-mount in meters.
146  */
147  void setPayload(double mass, double x, double y, double z);
148 
149  /**
150  * <p>
151  * Set the Tool Center Point (TCP).
152  * </p>
153  *
154  * Sets the transformation from the tool output flange coordinate system to
155  * the TCP as a pose.
156  *
157  * @param x Position part.
158  * @param y Position part.
159  * @param z Position part.
160  * @param rx Rotation part.
161  * @param ry Rotation part.
162  * @param rz Rotation part.
163  */
164  void setTcp(const std::vector<double> &pose);
165 
166  /**
167  * Start an if-conditional.
168  *
169  * @param expression the expression of the if-sentence. Not
170  * <code>null</code>.
171  */
172  void ifCondition(const std::string &expression);
173 
174  /**
175  * Start a negated if-conditional
176  *
177  * @param expression the expression of the negated if-sentence.
178  */
179  void ifNotCondition(const std::string &expression);
180 
181  /**
182  * Adds an else-if branch.
183  *
184  * @param expression the expression of the "else-if"-sentence.
185  */
186  void elseIfCondition(const std::string &expression);
187 
188  /**
189  * Adds an else branch.
190  *
191  */
192  void elseCondition();
193 
194  /**
195  * Starts a for-loop with tow loop invariants.
196  *
197  * @param count the loop counts.
198  * @param step the loop step.
199  */
200  void forCondition(int count, int step);
201 
202  /**
203  * Starts a while true loop.
204  *
205  */
206  void whileTrue();
207 
208  /**
209  * Starts a while-loop with a loop invariant.
210  *
211  * @param expression the loop invariant.
212  */
213  void whileCondition(const std::string &expression);
214 
215  /**
216  * Starts a while-loop with a negated loop invariant.
217  *
218  * @param expression the loop invariant that will be negated.
219  */
220  void whileNot(const std::string &expression);
221 
222  /**
223  * Start a thread definition with a given thread name.
224  *
225  * @param threadName the name of the new thread.
226  * @param loop_or_not the new thread loops or not.
227  */
228  void defineThread(const std::string &thread_name, bool loop_or_not);
229 
230  /**
231  * Start a previously defined thread.
232  *
233  * @param threadName The name of the thread that will be started.
234  */
235  void runThread(const std::string &thread_name);
236 
237  /**
238  * <p>
239  * Returns a registered variable name that can be used in a script.
240  * </p>
241  *
242  * <p>
243  * A variable is registered if it has been stored in a {@link DataModel}
244  * instance or used for the configuration of a built-in AuboScope program
245  * node.
246  * </p>
247  *
248  * <b>Please note:</b> The name of a variable in the script can be different
249  * from the value of {@link Variable#getDisplayName()}. You should not use
250  * the value of {@link Variable#getDisplayName()} in a script.
251  *
252  * @param variable a registered Variable. Not <code>null</code>.
253  * @return variable name that can be used in a script.
254  * @exception IllegalArgumentException if the <code>variable</code> was not
255  * registered in the data model or used for the configuration of a built-in
256  * AuboScope program node.
257  * @exception ClassCastException if the <code>variable</code> was not
258  * created by
259  * {@link domain/variable/VariableFactory}.
260  *
261  */
262  std::string getResolvedVariable(const std::string &variable_name);
263 
264  void increaseIndent();
265  void decreaseIndent();
266 
267 private:
268  friend class DataSwitch;
269  ScriptWriter();
270  void *d_{ nullptr };
271 };
272 
273 } // namespace aubo_scope
274 } // namespace arcs
275 
276 #endif // AUBO_SCOPE_SCRIPT_WRITER_H
ARCS_CLASS_FORWARD(GripForceCapability)
This interface provides support for generating Script code.
Definition: script_writer.h:15
#define ARCS_ABI_EXPORT
Definition: class_forward.h:16