$search
Classes | |
| class | AbsentNodeTab |
| struct | AbstractTreeNode |
| class | AeslBreakpointSidebar |
| class | AeslEditor |
| class | AeslEditorSidebar |
| struct | AeslEditorUserData |
| class | AeslHighlighter |
| class | AeslLineNumberSidebar |
| struct | ArithmeticAssignmentNode |
| class | ArrayAccessOutOfBounds |
| Exception: an array acces attempted to read past memory. More... | |
| struct | ArrayReadNode |
| struct | ArrayWriteNode |
| class | AsebaNetworkInterface |
| DBus interface for aseba network. More... | |
| struct | AssignmentNode |
| class | BasicFormatableString |
| struct | BinaryArithmeticNode |
| struct | BlockNode |
| Node for L"block", i.e. a vector of statements. More... | |
| class | BootloaderAck |
| Message for bootloader: acknowledge, with optional error code. More... | |
| class | BootloaderDataRead |
| Message for bootloader: data from the flash. More... | |
| class | BootloaderDescription |
| Message for bootloader: description of the flash memory layout. More... | |
| class | BootloaderInterface |
| Manage interactions with an aseba-compatible bootloader. More... | |
| class | BootloaderPageDataWrite |
| Message for bootloader: data for flash. More... | |
| class | BootloaderReadPage |
| Message for bootloader: read a page of flash. More... | |
| class | BootloaderReset |
| Message for bootloader: reset node. More... | |
| class | BootloaderWritePage |
| Message for bootloader: write a page of flash. More... | |
| class | BreakpointClear |
| Clear a breakpoint on a node. More... | |
| class | BreakpointClearAll |
| Clear all breakpoints on a node. More... | |
| class | BreakpointSet |
| Set a breakpoint on a node. More... | |
| class | BreakpointSetResult |
| A breakpoint has been set. More... | |
| struct | BytecodeElement |
| A bytecode element. More... | |
| struct | BytecodeVector |
| Bytecode array in the form of a dequeue, for construction. More... | |
| struct | ByteSwapper |
| ByteSwapper, code inspired by DPS (http://dps.epfl.ch/), released in GPL. More... | |
| struct | CallNode |
| struct | CallSubNode |
| class | ClickableLabel |
| class | CmdBootloaderInterface |
| class | CmdMessage |
| Commands messages talk to a specific node. More... | |
| struct | CommonDefinitions |
| Definitions common to several nodes, such as events or some constants. More... | |
| class | CompilationLogDialog |
| class | Compiler |
| Aseba Event Scripting Language compiler. More... | |
| class | CompilerTranslator |
| class | ConfigDialog |
| class | ConfigPage |
| class | DashelConnectionDialog |
| class | DashelInterface |
| class | DashelTarget |
| class | Description |
| Description of a node, local events and native functions are omitted and further received by other messages. More... | |
| class | DescriptionsManager |
| class | Disconnected |
| A node has disconnected from the network. More... | |
| class | DivisionByZero |
| Exception: division by zero. More... | |
| class | DraggableListWidget |
| class | Dump |
| class | EditorPage |
| class | EditorsPlotsTabWidget |
| struct | EmitNode |
| struct | Error |
| Compilation error. More... | |
| class | ErrorMessages |
| Return error messages based on error ID (needed to translate messages for other applications). More... | |
| struct | EventDeclNode |
| class | EventExecutionKilled |
| Exception: an event execution was killed by a new event. More... | |
| class | EventFilterInterface |
| DBus interface for an event filter. More... | |
| class | Exec |
| Execute an external command upon a given message. More... | |
| class | ExecutionStateChanged |
| The Program Counter or the flags have changed. More... | |
| class | FindDialog |
| class | FixedWidthTableView |
| struct | FoldedIfWhenNode |
| struct | FoldedWhileNode |
| class | FunctionParametersDialog |
| Dialog that let the user choose setup parameters for functions. More... | |
| class | GeneralPage |
| class | GetDescription |
| Request nodes to send their description. More... | |
| class | GetExecutionState |
| Request the current execution state of a node. More... | |
| class | GetVariables |
| Read some variables from a node. More... | |
| class | HelpBrowser |
| class | HelpViewer |
| class | HexFile |
| class | Hub |
| struct | IfWhenNode |
| struct | ImmediateNode |
| struct | InvasivePlugin |
| To access private members of MainWindow and its children, a plugin must inherit from this class. More... | |
| class | LinearCameraViewPlugin |
| class | LinearCameraViewVariablesDialog |
| struct | LoadNode |
| class | LocalEventDescription |
| Description of a local event available on a node, the description of the node itself must have been sent first. More... | |
| class | LocalVirtualMachine |
| The virtual machine running in local. More... | |
| class | MainWindow |
| class | MaskableNamedValuesVectorModel |
| struct | MemoryVectorNode |
| class | Message |
| Parent class of any message exchanged over the network. More... | |
| class | MessageTypesInitializer |
| Static class that fills a table of known messages types in its constructor. More... | |
| class | ModelAggregator |
| struct | NamedValue |
| A name - value pair. More... | |
| struct | NamedValuesVector |
| Generic vector of name - value pairs. More... | |
| class | NamedValuesVectorModel |
| class | NamedVariableDescription |
| Description of a named variable available on a node, the description of the node itself must have been sent first. More... | |
| class | NativeFunctionDescription |
| Description of a native function available on a node, the description of the node itself must have been sent first. More... | |
| class | NewNamedValueDialog |
| struct | Node |
| An abstract node of syntax tree. More... | |
| class | NodeSpecificError |
| A node as produced an error specific to it. More... | |
| class | NodeTab |
| struct | NodeToolInterface |
| A tool that is specific to a node. More... | |
| struct | NodeToolInterfaces |
| A list of NodeToolInterface pointers. More... | |
| struct | NodeToolRegistrar |
| Node tools are available per product id. More... | |
| struct | NodeToolRegistrer |
| class | Pause |
| Pause a node. More... | |
| class | Player |
| struct | PreLinkBytecode |
| Bytecode use for compilation previous to linking. More... | |
| struct | ProgramNode |
| Node for L"program", i.e. a block node with some special behaviour later on. More... | |
| class | QtBootloaderInterface |
| class | Reboot |
| Reboot a node, useful to go into its bootloader, if present. More... | |
| struct | ReconnectionDialog |
| class | Recorder |
| class | Reset |
| Reset a node. More... | |
| struct | ReturnNode |
| class | Run |
| Run a node. More... | |
| class | ScriptTab |
| class | SetBytecode |
| Upload bytecode to a node. More... | |
| class | SetVariables |
| Set some variables on a node. More... | |
| class | SignalingDescriptionsManager |
| Provides a signal/slot interface for the description manager. More... | |
| class | Sleep |
| struct | SourcePos |
| Position in a source file or string. First is line, second is column. More... | |
| class | SpinBoxDelegate |
| class | Step |
| Step a node. More... | |
| class | Stop |
| Stop a node. More... | |
| struct | StoreNode |
| struct | SubDeclNode |
| class | Switch |
| class | Target |
| The interface to an aseba network. Used to interact with the nodes. More... | |
| struct | TargetDescription |
| Description of target VM. More... | |
| class | TargetFunctionsModel |
| class | TargetVariablesModel |
| class | ThymioBootloaderDialog |
| class | ThymioButton |
| class | ThymioButtonSet |
| class | ThymioButtonsEvent |
| class | ThymioCircleAction |
| class | ThymioClapEvent |
| class | ThymioClickableButton |
| class | ThymioColorAction |
| class | ThymioCompiler |
| class | ThymioFaceButton |
| class | ThymioFlasherDialog |
| class | ThymioIRButton |
| class | ThymioIRButtonSet |
| class | ThymioIRCodeGenerator |
| class | ThymioIRSyntaxChecker |
| class | ThymioIRTypeChecker |
| class | ThymioIRVisitor |
| class | ThymioMemoryAction |
| class | ThymioMoveAction |
| class | ThymioProxEvent |
| class | ThymioProxGroundEvent |
| class | ThymioPushButton |
| class | ThymioScene |
| class | ThymioSoundAction |
| class | ThymioTapEvent |
| class | ThymioVisualProgramming |
| struct | TranslatableError |
| class | TreeChainsawFilter |
| struct | TupleVectorNode |
| struct | UnaryArithmeticAssignmentNode |
| struct | UnaryArithmeticNode |
| struct | UnifiedTime |
| Time or durations, in milliseconds. More... | |
| class | UserMessage |
| Any message sent by a script on a node. More... | |
| class | VariableListener |
| Classes that want to listen to variable changes should inherit from this class. More... | |
| class | Variables |
| Content of some variables. More... | |
| struct | WhileNode |
| class | WriteBytecode |
| Save the current bytecode of a node. More... | |
Typedefs | |
| typedef NamedValue | ConstantDefinition |
| An constant definition is a name - value pair. | |
| typedef NamedValuesVector | ConstantsDefinitions |
| Vector of constants definitions. | |
| typedef NamedValue | EventDescription |
| An event description is a name - value pair. | |
| typedef NamedValuesVector | EventsDescriptionsVector |
| Vector of events descriptions. | |
| typedef BasicFormatableString < char > | FormatableString |
| typedef std::map< int, std::pair< std::string, std::string > > | PortsMap |
| typedef std::vector< short int > | VariablesDataVector |
| Vector of data of variables. | |
| typedef std::vector< std::wstring > | VariablesNamesVector |
| Vector of names of variables. | |
| typedef BasicFormatableString < wchar_t > | WFormatableString |
Enumerations | |
| enum | ErrorCode { ERROR_BROKEN_TARGET = 0, ERROR_STACK_OVERFLOW, ERROR_SCRIPT_TOO_BIG, ERROR_VARIABLE_NOT_DEFINED, ERROR_VARIABLE_NOT_DEFINED_GUESS, ERROR_FUNCTION_NOT_DEFINED, ERROR_FUNCTION_NOT_DEFINED_GUESS, ERROR_CONSTANT_NOT_DEFINED, ERROR_CONSTANT_NOT_DEFINED_GUESS, ERROR_EVENT_NOT_DEFINED, ERROR_EVENT_NOT_DEFINED_GUESS, ERROR_EMIT_LOCAL_EVENT, ERROR_SUBROUTINE_NOT_DEFINED, ERROR_SUBROUTINE_NOT_DEFINED_GUESS, ERROR_LINE, ERROR_COL, ERROR_UNBALANCED_COMMENT_BLOCK, ERROR_SYNTAX, ERROR_INVALID_IDENTIFIER, ERROR_INVALID_HEXA_NUMBER, ERROR_INVALID_BINARY_NUMBER, ERROR_NUMBER_INVALID_BASE, ERROR_IN_NUMBER, ERROR_INTERNAL, ERROR_EXPECTING, ERROR_UINT12_OUT_OF_RANGE, ERROR_UINT16_OUT_OF_RANGE, ERROR_PINT16_OUT_OF_RANGE, ERROR_INT16_OUT_OF_RANGE, ERROR_PCONSTANT_OUT_OF_RANGE, ERROR_CONSTANT_OUT_OF_RANGE, ERROR_EXPECTING_ONE_OF, ERROR_NOT_ENOUGH_TEMP_SPACE, ERROR_MISPLACED_VARDEF, ERROR_EXPECTING_IDENTIFIER, ERROR_VAR_ALREADY_DEFINED, ERROR_VAR_CONST_COLLISION, ERROR_UNDEFINED_SIZE, ERROR_NOT_ENOUGH_SPACE, ERROR_EXPECTING_ASSIGNMENT, ERROR_FOR_NULL_STEPS, ERROR_FOR_START_HIGHER_THAN_END, ERROR_FOR_START_LOWER_THAN_END, ERROR_EVENT_ALREADY_IMPL, ERROR_EVENT_WRONG_ARG_SIZE, ERROR_SUBROUTINE_ALREADY_DEF, ERROR_INDEX_EXPECTING_CONSTANT, ERROR_INDEX_WRONG_END, ERROR_SIZE_IS_NEGATIVE, ERROR_SIZE_IS_NULL, ERROR_NOT_CONST_EXPR, ERROR_FUNCTION_HAS_NO_ARG, ERROR_FUNCTION_NO_ENOUGH_ARG, ERROR_FUNCTION_WRONG_ARG_SIZE, ERROR_FUNCTION_WRONG_ARG_SIZE_TEMPLATE, ERROR_FUNCTION_TOO_MANY_ARG, ERROR_UNARY_ARITH_BUILD_UNEXPECTED, ERROR_INCORRECT_LEFT_VALUE, ERROR_ARRAY_OUT_OF_BOUND, ERROR_ARRAY_SIZE_MISMATCH, ERROR_IF_VECTOR_CONDITION, ERROR_WHILE_VECTOR_CONDITION, ERROR_ARRAY_ILLEGAL_ACCESS, ERROR_INFINITE_LOOP, ERROR_DIVISION_BY_ZERO, ERROR_ABS_NOT_POSSIBLE, ERROR_ARRAY_OUT_OF_BOUND_READ, ERROR_ARRAY_OUT_OF_BOUND_WRITE, ERROR_EXPECTING_TYPE, ERROR_EXPECTING_CONDITION, ERROR_TOKEN_END_OF_STREAM, ERROR_TOKEN_STR_when, ERROR_TOKEN_STR_emit, ERROR_TOKEN_STR_for, ERROR_TOKEN_STR_in, ERROR_TOKEN_STR_step, ERROR_TOKEN_STR_while, ERROR_TOKEN_STR_do, ERROR_TOKEN_STR_if, ERROR_TOKEN_STR_then, ERROR_TOKEN_STR_else, ERROR_TOKEN_STR_elseif, ERROR_TOKEN_STR_end, ERROR_TOKEN_STR_var, ERROR_TOKEN_STR_call, ERROR_TOKEN_STR_sub, ERROR_TOKEN_STR_callsub, ERROR_TOKEN_STR_onevent, ERROR_TOKEN_STR_abs, ERROR_TOKEN_STR_return, ERROR_TOKEN_STRING_LITERAL, ERROR_TOKEN_INT_LITERAL, ERROR_TOKEN_PAR_OPEN, ERROR_TOKEN_PAR_CLOSE, ERROR_TOKEN_BRACKET_OPEN, ERROR_TOKEN_BRACKET_CLOSE, ERROR_TOKEN_COLON, ERROR_TOKEN_COMMA, ERROR_TOKEN_ASSIGN, ERROR_TOKEN_OP_OR, ERROR_TOKEN_OP_AND, ERROR_TOKEN_OP_NOT, ERROR_TOKEN_OP_BIT_OR, ERROR_TOKEN_OP_BIT_XOR, ERROR_TOKEN_OP_BIT_AND, ERROR_TOKEN_OP_BIT_NOT, ERROR_TOKEN_OP_BIT_OR_EQUAL, ERROR_TOKEN_OP_BIT_XOR_EQUAL, ERROR_TOKEN_OP_BIT_AND_EQUAL, ERROR_TOKEN_OP_EQUAL, ERROR_TOKEN_OP_NOT_EQUAL, ERROR_TOKEN_OP_BIGGER, ERROR_TOKEN_OP_BIGGER_EQUAL, ERROR_TOKEN_OP_SMALLER, ERROR_TOKEN_OP_SMALLER_EQUAL, ERROR_TOKEN_OP_SHIFT_LEFT, ERROR_TOKEN_OP_SHIFT_RIGHT, ERROR_TOKEN_OP_SHIFT_LEFT_EQUAL, ERROR_TOKEN_OP_SHIFT_RIGHT_EQUAL, ERROR_TOKEN_OP_ADD, ERROR_TOKEN_OP_NEG, ERROR_TOKEN_OP_ADD_EQUAL, ERROR_TOKEN_OP_NEG_EQUAL, ERROR_TOKEN_OP_PLUS_PLUS, ERROR_TOKEN_OP_MINUS_MINUS, ERROR_TOKEN_OP_MULT, ERROR_TOKEN_OP_DIV, ERROR_TOKEN_OP_MOD, ERROR_TOKEN_OP_MULT_EQUAL, ERROR_TOKEN_OP_DIV_EQUAL, ERROR_TOKEN_OP_MOD_EQUAL, ERROR_TOKEN_UNKNOWN, ERROR_UNKNOWN_ERROR, ERROR_END } |
| enum | InNextState { NOT_IN_NEXT, WAITING_INITAL_PC, WAITING_LINE_CHANGE } |
| enum | LocalContext { UnknownContext, VarDefContext, LeftValueContext, FunctionContext, EventContext, GeneralContext } |
| enum | ThymioButtonType { THYMIO_CIRCULAR_BUTTON = 0, THYMIO_TRIANGULAR_BUTTON, THYMIO_RECTANGULAR_BUTTON } |
| enum | ThymioIRButtonName { THYMIO_BUTTONS_IR = 0, THYMIO_PROX_IR, THYMIO_PROX_GROUND_IR, THYMIO_TAP_IR, THYMIO_CLAP_IR, THYMIO_MOVE_IR, THYMIO_COLOR_IR, THYMIO_CIRCLE_IR, THYMIO_SOUND_IR, THYMIO_MEMORY_IR } |
| enum | ThymioIRErrorCode { THYMIO_NO_ERROR = 0, THYMIO_MISSING_EVENT, THYMIO_MISSING_ACTION, THYMIO_EVENT_MULTISET, THYMIO_INVALID_CODE } |
| enum | ThymioIRErrorType { THYMIO_NO_TYPE_ERROR = 0, THYMIO_SYNTAX_ERROR, THYMIO_TYPE_ERROR, THYMIO_CODE_ERROR } |
| enum | ThymioSmileType { THYMIO_SMILE_BUTTON = 0, THYMIO_NEUTRAL_BUTTON, THYMIO_FROWN_BUTTON } |
Functions | |
| std::wstring | binaryOperatorToString (AsebaBinaryOperator op) |
| Return the string corresponding to the binary operator. | |
| NodeTab::CompilationResult * | compilationThread (const TargetDescription targetDescription, const CommonDefinitions commonDefinitions, QString source, bool dump) |
| static uint16 | crc_xmodem_update (uint16 crc, const uint8 *data, size_t len) |
| static uint16 | crc_xmodem_update (uint16 crc, uint8 data) |
| uint16 | crcXModem (const uint16 oldCrc, const uint16 v) |
| Update the XModem CRC (x^16 + x^12 + x^5 + 1 (0x1021)) with a uint16 value. | |
| uint16 | crcXModem (const uint16 oldCrc, const std::wstring &s) |
| Update the XModem CRC (x^16 + x^12 + x^5 + 1 (0x1021)) with a wstring. | |
| static uint16 | crcXModem (const uint16 oldCrc, const QString &s) |
| template<typename C > | |
| NodeToolInterface * | createInstance (NodeTab *node) |
| Create an instance of C, passing node to its constructor. | |
| void | dumpCommandList (ostream &stream) |
| Show list of known commands. | |
| void | dumpHelp (ostream &stream, const char *programName) |
| Show usage. | |
| void | dumpTime (std::ostream &stream, bool raw=false) |
| Dump the current time to a stream. | |
| void | dumpVersion (std::ostream &stream) |
| Show version. | |
| template<class T > | |
| unsigned int | editDistance (const T &s1, const T &s2, const unsigned maxDist) |
| Compute the edit distance between two vector-style containers, inspired from http://en.wikibooks.org/wiki/Algorithm_Implementation/Strings/Levenshtein_distance#C.2B.2B. | |
| void | errorBootloader (const string &message) |
| Produce an error message and quit. | |
| void | errorHexFile (const string &message) |
| Produce an error message and quit. | |
| void | errorMissingArgument (const char *programName) |
| Produce an error message and dump help and quit. | |
| void | errorOpenFile (const char *fileName) |
| Produce an error message and quit. | |
| void | errorReadPage (int pageNumber) |
| Produce an error message and quit. | |
| void | errorServerDisconnected () |
| Produce an error message and quit. | |
| void | errorUnknownCommand (const char *cmd) |
| Produce an error message and dump help and quit. | |
| template<typename MapType > | |
| MapType::const_iterator | findInTable (const MapType &map, const std::wstring &name, const SourcePos &pos, const ErrorCode notFoundError, const ErrorCode misspelledError) |
| Helper function to find for something in one of the map, using edit-distance to check for candidates if not found. | |
| Values | fromAsebaVector (const std::vector< sint16 > &values) |
| template<typename T > | |
| bool | isPOT (T number) |
| Return true if number is a power of two. | |
| template<typename Derived , typename Base > | |
| static Derived | polymorphic_downcast (Base base) |
| Asserts a dynamic cast. Similar to the one in boost/cast.hpp. | |
| template<typename Derived , typename Base > | |
| static Derived | polymorphic_downcast_or_null (Base base) |
| Asserts a dynamic cast or a null. Similar to the one in boost/cast.hpp. | |
| int | processCommand (Stream *stream, int argc, char *argv[]) |
| Process a command, return the number of arguments eaten (not counting the command itself). | |
| void | sendBytecode (std::vector< Message * > &messagesVector, uint16 dest, const std::vector< uint16 > &bytecode) |
| Call the SetBytecode multiple time in order to send all the bytecode. | |
| void | sendBytecode (Dashel::Stream *stream, uint16 dest, const std::vector< uint16 > &bytecode) |
| Call the SetBytecode multiple time in order to send all the bytecode. | |
| template<typename T > | |
| unsigned | shiftFromPOT (T number) |
| If number is a power of two, number = (1 << shift) and this function returns shift, otherwise return value is undefined. | |
| template<typename T > | |
| void | swapEndian (T &v) |
| template<typename T > | |
| T | swapEndianCopy (const T &v) |
| std::vector< sint16 > | toAsebaVector (const Values &values) |
| std::wstring | unaryOperatorToString (AsebaUnaryOperator op) |
| Return the string corresponding to the unary operator. | |
| std::wstring | UTF8ToWString (const std::string &s) |
| Transform a UTF8 string into a wstring, this function is thread-safe. | |
| static void | write16 (QIODevice &dev, const VariablesDataVector &data, const char *varName) |
| static void | write16 (QIODevice &dev, const uint16 v) |
| std::string | WStringToUTF8 (const std::wstring &s) |
| Transform a wstring into an UTF8 string, this function is thread-safe. | |
Variables | |
| static const wchar_t * | error_map [ERROR_END] |
| class Aseba::MessageTypesInitializer | messageTypesInitializer |
| Static class that fills a table of known messages types in its constructor. | |
| static NodeToolRegistrer | nodeToolRegistrer |
| typedef std::map<int, std::pair<std::string, std::string> > Aseba::PortsMap |
Definition at line 28 of file ThymioFlasher.cpp.
| enum Aseba::ErrorCode |
Definition at line 15 of file errors_code.h.
| THYMIO_BUTTONS_IR | |
| THYMIO_PROX_IR | |
| THYMIO_PROX_GROUND_IR | |
| THYMIO_TAP_IR | |
| THYMIO_CLAP_IR | |
| THYMIO_MOVE_IR | |
| THYMIO_COLOR_IR | |
| THYMIO_CIRCLE_IR | |
| THYMIO_SOUND_IR | |
| THYMIO_MEMORY_IR |
Definition at line 14 of file ThymioIntermediateRepresentation.h.
| THYMIO_NO_ERROR | |
| THYMIO_MISSING_EVENT | |
| THYMIO_MISSING_ACTION | |
| THYMIO_EVENT_MULTISET | |
| THYMIO_INVALID_CODE |
Definition at line 28 of file ThymioIntermediateRepresentation.h.
Definition at line 37 of file ThymioIntermediateRepresentation.h.
| void Aseba::dumpCommandList | ( | ostream & | stream | ) |
| void Aseba::dumpHelp | ( | ostream & | stream, | |
| const char * | programName | |||
| ) |
| void Aseba::dumpVersion | ( | std::ostream & | stream | ) |
| void Aseba::errorBootloader | ( | const string & | message | ) |
| void Aseba::errorHexFile | ( | const string & | message | ) |
| void Aseba::errorMissingArgument | ( | const char * | programName | ) |
| void Aseba::errorOpenFile | ( | const char * | fileName | ) |
| void Aseba::errorReadPage | ( | int | pageNumber | ) |
| void Aseba::errorServerDisconnected | ( | ) |
| void Aseba::errorUnknownCommand | ( | const char * | cmd | ) |
| int Aseba::processCommand | ( | Stream * | stream, | |
| int | argc, | |||
| char * | argv[] | |||
| ) |
Static class that fills a table of known messages types in its constructor.
static instance, used only to have its constructor called on startup