From 9695e5c9051d331278288a071c1353ae7214c4c2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 18 Dec 2009 16:30:25 +0000 Subject: Update to use stdint/stdbool.h git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2384 42af7a65-404d-4744-a932-0658087f49c3 --- misc/pascal/insn32/include/builtins.h | 16 +- misc/pascal/insn32/include/pexec.h | 316 +-- misc/pascal/insn32/include/rinsn32.h | 442 +-- misc/pascal/insn32/libinsn/paddopcode.c | 195 +- misc/pascal/insn32/libinsn/paddtmpopcode.c | 196 +- misc/pascal/insn32/libinsn/pdasm.c | 865 +++--- misc/pascal/insn32/libinsn/pgen.c | 765 +++--- misc/pascal/insn32/libinsn/pgetopcode.c | 254 +- misc/pascal/insn32/libinsn/preloc.c | 296 +- misc/pascal/insn32/libinsn/presettmpopcodewrite.c | 196 +- misc/pascal/insn32/plist/plist.c | 775 +++--- misc/pascal/insn32/popt/pcopt.c | 1679 ++++++------ misc/pascal/insn32/popt/pfopt.c | 417 +-- misc/pascal/insn32/popt/plopt.c | 429 +-- misc/pascal/insn32/popt/psopt.c | 273 +- misc/pascal/insn32/regm/regm.c | 683 ++--- misc/pascal/insn32/regm/regm.h | 132 +- misc/pascal/insn32/regm/regm_pass1.c | 560 ++-- misc/pascal/insn32/regm/regm_pass2.c | 3051 +++++++++++---------- misc/pascal/insn32/regm/regm_pass2.h | 134 +- misc/pascal/insn32/regm/regm_registers2.c | 1083 ++++---- misc/pascal/insn32/regm/regm_registers2.h | 636 ++--- misc/pascal/insn32/regm/regm_tree.c | 675 ++--- misc/pascal/insn32/regm/regm_tree.h | 243 +- 24 files changed, 7183 insertions(+), 7128 deletions(-) (limited to 'misc') diff --git a/misc/pascal/insn32/include/builtins.h b/misc/pascal/insn32/include/builtins.h index c60e44eea..04aacfde9 100644 --- a/misc/pascal/insn32/include/builtins.h +++ b/misc/pascal/insn32/include/builtins.h @@ -2,7 +2,7 @@ * builtins.h * Definitions of built-in function calls. * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -38,7 +38,13 @@ #define __BUILTINS_H /*********************************************************************** - * Definitions + * Included Files + ***********************************************************************/ + +#include + +/*********************************************************************** + * Pre-processor Definitions ***********************************************************************/ #define MAX_BUILTIN_ARGS 3 @@ -436,9 +442,9 @@ struct regm_builtin_s { const char *szName; - uint32 wRetSize; - uint32 nParms; - uint32 wArgSize[MAX_BUILTIN_ARGS]; + uint32_t wRetSize; + uint32_t nParms; + uint32_t wArgSize[MAX_BUILTIN_ARGS]; }; #endif /* __BUILTINS_H */ diff --git a/misc/pascal/insn32/include/pexec.h b/misc/pascal/insn32/include/pexec.h index c8b530afc..67227ff3a 100644 --- a/misc/pascal/insn32/include/pexec.h +++ b/misc/pascal/insn32/include/pexec.h @@ -1,158 +1,160 @@ -/**************************************************************************** - * pexec.h - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#ifndef __PEXEC_H -#define __PEXEC_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -#define BPERI 2 -#define ITOBSTACK(i) ((i) << 1) -#define BTOISTACK(i) ((i) >> 1) -#define ROUNDBTOI(i) (((i) + 1) >> 1) - -/**************************************************************************** - * Type Definitions - ****************************************************************************/ - -typedef uint32 ustack_t; /* Stack values are 16-bits in length */ -typedef sint32 sstack_t; -typedef uint32 addr_t; /* Addresses are 16-bits in length */ -typedef uint16 level_t; /* Limits to MAXUINT16 levels */ - -union stack_u -{ - ustack_t *i; - ubyte *b; -}; -typedef union stack_u stackType; - -/* This structure describes the parameters needed to initialize the p-code - * interpreter. - */ - -struct pexec_attr_s -{ - /* Instruction space (I-Space) */ - - FAR ubyte *ispace; /* Allocated I-Space containing p-code data */ - addr_t entry; /* Entry point */ - addr_t maxpc; /* Last valid p-code address */ - - /* Read-only data block */ - - FAR ubyte *rodata; /* Address of read-only data block */ - addr_t rosize; /* Size of read-only data block */ - - /* Allocate for variable storage */ - - addr_t varsize; /* Variable storage size */ - addr_t strsize; /* String storage size */ -}; - -/* This structure defines the current state of the p-code interpreter */ - -struct pexec_s -{ - /* This is the emulated P-Machine stack (D-Space) */ - - stackType dstack; - - /* This is the emulated P-Machine instruction space (I-Space) */ - - FAR ubyte *ispace; - - /* Address of last valid P-Code */ - - addr_t maxpc; - - /* These are the emulated P-Machine registers: - * - * spb: Base of the stack - * sp: The Pascal stack pointer - * lsp: Level stack pointer - * csp: The current top of the stack used to manage string - * storage - * fp: Base Register of the current stack frame. Holds the address - * of the base of the stack frame of the current block. - * fop: Pointer to section containing read-only data - * pc: Holds the current p-code location - */ - - addr_t spb; /* Pascal stack base */ - addr_t sp; /* Pascal stack pointer */ - addr_t lsp; /* Level stack pointer */ - addr_t csp; /* Character stack pointer */ - addr_t fp; /* Base of the current frame */ - addr_t rop; /* Read-only data pointer */ - addr_t pc; /* Program counter */ - - /* Info needed to perform a simulated reset */ - - addr_t strsize; /* String stack size */ - addr_t rosize; /* Read-only stack size */ - addr_t entry; /* Entry point */ - addr_t stacksize; /* (debug only) */ -}; - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -EXTERN FAR struct pexec_s *pload(const char *filename, addr_t varsize, addr_t strsize); -EXTERN FAR struct pexec_s *pexec_init(struct pexec_attr_s *attr); -EXTERN int pexec(FAR struct pexec_s *st); -EXTERN void pexec_reset(struct pexec_s *st); -EXTERN void pexec_release(struct pexec_s *st); - -#undef EXTERN -#ifdef __cplusplus -} -#endif - +/**************************************************************************** + * pexec.h + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __PEXEC_H +#define __PEXEC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define BPERI 2 +#define ITOBSTACK(i) ((i) << 1) +#define BTOISTACK(i) ((i) >> 1) +#define ROUNDBTOI(i) (((i) + 1) >> 1) + +/**************************************************************************** + * Type Definitions + ****************************************************************************/ + +typedef uint32_t ustack_t; /* Stack values are 16-bits in length */ +typedef int32_t sstack_t; +typedef uint32_t addr_t; /* Addresses are 16-bits in length */ +typedef uint16_t level_t; /* Limits to MAXUINT16 levels */ + +union stack_u +{ + ustack_t *i; + uint8_t *b; +}; +typedef union stack_u stackType; + +/* This structure describes the parameters needed to initialize the p-code + * interpreter. + */ + +struct pexec_attr_s +{ + /* Instruction space (I-Space) */ + + FAR uint8_t *ispace; /* Allocated I-Space containing p-code data */ + addr_t entry; /* Entry point */ + addr_t maxpc; /* Last valid p-code address */ + + /* Read-only data block */ + + FAR uint8_t *rodata; /* Address of read-only data block */ + addr_t rosize; /* Size of read-only data block */ + + /* Allocate for variable storage */ + + addr_t varsize; /* Variable storage size */ + addr_t strsize; /* String storage size */ +}; + +/* This structure defines the current state of the p-code interpreter */ + +struct pexec_s +{ + /* This is the emulated P-Machine stack (D-Space) */ + + stackType dstack; + + /* This is the emulated P-Machine instruction space (I-Space) */ + + FAR uint8_t *ispace; + + /* Address of last valid P-Code */ + + addr_t maxpc; + + /* These are the emulated P-Machine registers: + * + * spb: Base of the stack + * sp: The Pascal stack pointer + * lsp: Level stack pointer + * csp: The current top of the stack used to manage string + * storage + * fp: Base Register of the current stack frame. Holds the address + * of the base of the stack frame of the current block. + * fop: Pointer to section containing read-only data + * pc: Holds the current p-code location + */ + + addr_t spb; /* Pascal stack base */ + addr_t sp; /* Pascal stack pointer */ + addr_t lsp; /* Level stack pointer */ + addr_t csp; /* Character stack pointer */ + addr_t fp; /* Base of the current frame */ + addr_t rop; /* Read-only data pointer */ + addr_t pc; /* Program counter */ + + /* Info needed to perform a simulated reset */ + + addr_t strsize; /* String stack size */ + addr_t rosize; /* Read-only stack size */ + addr_t entry; /* Entry point */ + addr_t stacksize; /* (debug only) */ +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +EXTERN FAR struct pexec_s *pload(const char *filename, addr_t varsize, addr_t strsize); +EXTERN FAR struct pexec_s *pexec_init(struct pexec_attr_s *attr); +EXTERN int pexec(FAR struct pexec_s *st); +EXTERN void pexec_reset(struct pexec_s *st); +EXTERN void pexec_release(struct pexec_s *st); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + #endif /* __PEXEC_H */ \ No newline at end of file diff --git a/misc/pascal/insn32/include/rinsn32.h b/misc/pascal/insn32/include/rinsn32.h index f2a89e5fa..8894023ff 100644 --- a/misc/pascal/insn32/include/rinsn32.h +++ b/misc/pascal/insn32/include/rinsn32.h @@ -1,216 +1,226 @@ -/*********************************************************************** - * rinsn32.h - * 32-bit register module instruction definitions - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ***********************************************************************/ - -#ifndef __RINSN32_H -#define __RINSN32_H - -/* 32-bit op-code bit definitions - * - * Machine model: - * - * SPB 32-bit Pascal stack base address - * SP 32-bit Pascal stack pointer - * LSP 32-bit level stack pointer - * CSB 32-bit character stack base address - * PC 32-bit program counter - * ZRO 32-bit register containing zero (like MIPS) - * Rn 32-bit general purpose registers - * - * Parameters passed in registers up to a limit. Parameters - * beyond the limit are passed on the stack. Return values - * are provided in these same registers. - * - * Instruction forms - * - * FORM 1: , - * FORM 2: , - * FORM 3: , , - * , , - * FORM 4: - * - * Where - * operation code - * [cc] optional conditional execution - * [S] optional set condition code - * register holding the result - * register holding data to be stored. - * register holding the first operand - * One of or - * register holding the second operand - * Immediate constant data (short). - * Word offset from current PC - * - * NOTE: This instruction set is inspired by the ARM instruction - * set, but is intended to be a general register model. It does - * not exploit certain ARM-isms such as "flexible" operands, conditional - * execution, post-incrementing, pre-incrementing, pc-relative addressing, - * optional register writeback, or ldm/stm with register sets, etc. - */ - -#define FORM1(o) (((o) & 0xe0) == 0x00) -#define FORM1R(o) (((o) & 0xf0) == 0x00) -#define FORM1I(o) (((o) & 0xf0) == 0x10) -#define FORM1O(o) ((o) & 0x0f) - -#define FORM2(o) (((o) & 0xe0) == 0x20) -#define FORM2R(o) (((o) & 0xf0) == 0x20) -#define FORM2I(o) (((o) & 0xf0) == 0x30) -#define FORM2O(o) ((o) & 0x0f) - -#define FORM3(o) (((o) & 0x80) == 0x80) -#define FORM3R(o) (((o) & 0xc0) == 0x80) -#define FORM3I(o) (((o) & 0xc0) == 0xc0) -#define FORM3O(o) ((o) & 0x3f) - -#define FORM4(o) (((o) & 0xc0) == 0x40) -#define FORM3O(o) ((o) & 0x3f) - -struct rinsn_u -{ - ubyte opcode; - union { - struct { - uint32 rop1; - uint32 rop2; - } r1; - struct { - uint32 rop1; - uint32 im2; - } i1; - struct { - uint32 rdest; - uint32 rop; - } r2; - struct { - uint32 rdest; - uint32 im; - } i2; - struct { - uint32 rdest; - uint32 rop1; - uint32 rop2; - } r3; - struct { - uint32 rdest; - uint32 rop1; - uint32 im2; - } i3; - struct { - uint32 offset; - } i4; - } f; -}; -typedef struct rinsn_u RINSN32; - -/* FORM 1: Comparisons */ - -#define rCMP (0x00) /* Form 1: set after - */ -#define rCMPI (0x10) /* Form 1: set after - */ -#define rCMN (0x01) /* Form 1: set after + */ -#define rCMNI (0x11) /* Form 1: set after + */ - -/* FORM 2: Data movement */ - -#define rMOV (0x20) /* Form 1: = */ -#define rMOVI (0x30) /* Form 1: = */ -#define rMVN (0x21) /* Form 1: = ~ */ -#define rMVNI (0x31) /* Form 1: = ~ */ - -/* FORM 4: Program control */ - -#define rB (0x40) /* PC += << 2 */ -#define rBEQ (0x41) /* if ->EQ, PC += << 2 */ -#define rBNE (0x42) /* if ->NEQ, PC += << 2 */ -#define rBLT (0x43) /* if ->LT, PC += << 2 */ -#define rBGTE (0x44) /* if ->GTE, PC += << 2 */ -#define rBGT (0x45) /* if ->GT, PC += << 2 */ -#define rBLTE (0x46) /* if ->KTE, PC += << 2 */ -#define rBL (0x47) /* LR=next PC, PC += << 2 */ - -/* FORM 3: Arithmetic and logical operations */ - -#define rADD (0x80) /* Form 3: = + */ -#define rADDI (0xc0) /* Form 3: = + */ -#define rSUB (0x81) /* Form 3: = - */ -#define rSUBI (0xc1) /* Form 3: = - */ -#define rRSB (0x82) /* Form 3: = - + */ -#define rRSBI (0xc2) /* Form 3: = - + */ -#define rMUL (0x83) /* Form 3: = * */ -#define rMULI (0xc3) /* Form 3: = * */ -#define rDIV (0x84) /* Form 3: = / */ -#define rDIVI (0xc4) /* Form 3: = / */ -#define rMOD (0x85) /* Form 3: = % */ -#define rMODI (0xc5) /* Form 3: = % */ -#define rSLL (0x86) /* Form 3: = << */ -#define rSLLI (0xc6) /* Form 3: = << */ -#define rSRL (0x87) /* Form 3: = >> */ -#define rSRLI (0xc7) /* Form 3: = >> */ -#define rSRA (0x88) /* Form 3: = >> */ -#define rSRAI (0xc8) /* Form 3: = >> */ -#define rOR (0x89) /* Form 3: = | */ -#define rORI (0xc9) /* Form 3: = | */ -#define rAND (0x8a) /* Form 3: = & */ -#define rANDI (0xca) /* Form 3: = & */ -#define rXOR (0x8b) /* Form 3: = xor */ -#define rXORI (0xcb) /* Form 3: = xor */ -#define rANDN (0x8c) /* Form 3: = & ~ */ -#define rANDNI (0xcc) /* Form 3: = & ~ */ - -/* FORM 3: Loads and stores */ - -#define rLD (0x90) /* Form 3: = ( + ) */ -#define rLDI (0xd0) /* Form 3: = ( + ( << 2)) */ -#define rLDH (0x91) /* Form 3: = ( + ) */ -#define rLDIH (0xd1) /* Form 3: = ( + ( << 1)) */ -#define rLDB (0x92) /* Form 3: = ( + ) */ -#define rLDIB (0xd2) /* Form 3: = ( + ) */ - -#define rLDM (0xd3) /* Form 3: Load registers. Source - * address is roperand1, first dest register is - * , register count is */ - -#define rST (0x94) /* Form 3: ( + ) = */ -#define rSTI (0xd4) /* Form 3: ( + ( << 2)) = */ -#define rSTH (0x95) /* Form 3: ( + ) = */ -#define rSTIH (0xd5) /* Form 3: ( + ( << 1)) = */ -#define rSTB (0x96) /* Form 3: ( + ) = */ -#define rSTIB (0xd6) /* Form 3: ( + ) = */ - -#define rSTM (0xd7) /* Form 3: Store registers. Destination - * address is roperand1, first source register is - * , register count is */ - -#endif /* __RINSN32_H */ +/*********************************************************************** + * rinsn32.h + * 32-bit register module instruction definitions + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ***********************************************************************/ + +#ifndef __RINSN32_H +#define __RINSN32_H + +/*********************************************************************** + * Included Files + ***********************************************************************/ + +#include + +/*********************************************************************** + * Pre-processor Definitions + ***********************************************************************/ + +/* 32-bit op-code bit definitions + * + * Machine model: + * + * SPB 32-bit Pascal stack base address + * SP 32-bit Pascal stack pointer + * LSP 32-bit level stack pointer + * CSB 32-bit character stack base address + * PC 32-bit program counter + * ZRO 32-bit register containing zero (like MIPS) + * Rn 32-bit general purpose registers + * + * Parameters passed in registers up to a limit. Parameters + * beyond the limit are passed on the stack. Return values + * are provided in these same registers. + * + * Instruction forms + * + * FORM 1: , + * FORM 2: , + * FORM 3: , , + * , , + * FORM 4: + * + * Where + * operation code + * [cc] optional conditional execution + * [S] optional set condition code + * register holding the result + * register holding data to be stored. + * register holding the first operand + * One of or + * register holding the second operand + * Immediate constant data (short). + * Word offset from current PC + * + * NOTE: This instruction set is inspired by the ARM instruction + * set, but is intended to be a general register model. It does + * not exploit certain ARM-isms such as "flexible" operands, conditional + * execution, post-incrementing, pre-incrementing, pc-relative addressing, + * optional register writeback, or ldm/stm with register sets, etc. + */ + +#define FORM1(o) (((o) & 0xe0) == 0x00) +#define FORM1R(o) (((o) & 0xf0) == 0x00) +#define FORM1I(o) (((o) & 0xf0) == 0x10) +#define FORM1O(o) ((o) & 0x0f) + +#define FORM2(o) (((o) & 0xe0) == 0x20) +#define FORM2R(o) (((o) & 0xf0) == 0x20) +#define FORM2I(o) (((o) & 0xf0) == 0x30) +#define FORM2O(o) ((o) & 0x0f) + +#define FORM3(o) (((o) & 0x80) == 0x80) +#define FORM3R(o) (((o) & 0xc0) == 0x80) +#define FORM3I(o) (((o) & 0xc0) == 0xc0) +#define FORM3O(o) ((o) & 0x3f) + +#define FORM4(o) (((o) & 0xc0) == 0x40) +#define FORM3O(o) ((o) & 0x3f) + +struct rinsn_u +{ + uint8_t opcode; + union { + struct { + uint32_t rop1; + uint32_t rop2; + } r1; + struct { + uint32_t rop1; + uint32_t im2; + } i1; + struct { + uint32_t rdest; + uint32_t rop; + } r2; + struct { + uint32_t rdest; + uint32_t im; + } i2; + struct { + uint32_t rdest; + uint32_t rop1; + uint32_t rop2; + } r3; + struct { + uint32_t rdest; + uint32_t rop1; + uint32_t im2; + } i3; + struct { + uint32_t offset; + } i4; + } f; +}; +typedef struct rinsn_u RINSN32; + +/* FORM 1: Comparisons */ + +#define rCMP (0x00) /* Form 1: set after - */ +#define rCMPI (0x10) /* Form 1: set after - */ +#define rCMN (0x01) /* Form 1: set after + */ +#define rCMNI (0x11) /* Form 1: set after + */ + +/* FORM 2: Data movement */ + +#define rMOV (0x20) /* Form 1: = */ +#define rMOVI (0x30) /* Form 1: = */ +#define rMVN (0x21) /* Form 1: = ~ */ +#define rMVNI (0x31) /* Form 1: = ~ */ + +/* FORM 4: Program control */ + +#define rB (0x40) /* PC += << 2 */ +#define rBEQ (0x41) /* if ->EQ, PC += << 2 */ +#define rBNE (0x42) /* if ->NEQ, PC += << 2 */ +#define rBLT (0x43) /* if ->LT, PC += << 2 */ +#define rBGTE (0x44) /* if ->GTE, PC += << 2 */ +#define rBGT (0x45) /* if ->GT, PC += << 2 */ +#define rBLTE (0x46) /* if ->KTE, PC += << 2 */ +#define rBL (0x47) /* LR=next PC, PC += << 2 */ + +/* FORM 3: Arithmetic and logical operations */ + +#define rADD (0x80) /* Form 3: = + */ +#define rADDI (0xc0) /* Form 3: = + */ +#define rSUB (0x81) /* Form 3: = - */ +#define rSUBI (0xc1) /* Form 3: = - */ +#define rRSB (0x82) /* Form 3: = - + */ +#define rRSBI (0xc2) /* Form 3: = - + */ +#define rMUL (0x83) /* Form 3: = * */ +#define rMULI (0xc3) /* Form 3: = * */ +#define rDIV (0x84) /* Form 3: = / */ +#define rDIVI (0xc4) /* Form 3: = / */ +#define rMOD (0x85) /* Form 3: = % */ +#define rMODI (0xc5) /* Form 3: = % */ +#define rSLL (0x86) /* Form 3: = << */ +#define rSLLI (0xc6) /* Form 3: = << */ +#define rSRL (0x87) /* Form 3: = >> */ +#define rSRLI (0xc7) /* Form 3: = >> */ +#define rSRA (0x88) /* Form 3: = >> */ +#define rSRAI (0xc8) /* Form 3: = >> */ +#define rOR (0x89) /* Form 3: = | */ +#define rORI (0xc9) /* Form 3: = | */ +#define rAND (0x8a) /* Form 3: = & */ +#define rANDI (0xca) /* Form 3: = & */ +#define rXOR (0x8b) /* Form 3: = xor */ +#define rXORI (0xcb) /* Form 3: = xor */ +#define rANDN (0x8c) /* Form 3: = & ~ */ +#define rANDNI (0xcc) /* Form 3: = & ~ */ + +/* FORM 3: Loads and stores */ + +#define rLD (0x90) /* Form 3: = ( + ) */ +#define rLDI (0xd0) /* Form 3: = ( + ( << 2)) */ +#define rLDH (0x91) /* Form 3: = ( + ) */ +#define rLDIH (0xd1) /* Form 3: = ( + ( << 1)) */ +#define rLDB (0x92) /* Form 3: = ( + ) */ +#define rLDIB (0xd2) /* Form 3: = ( + ) */ + +#define rLDM (0xd3) /* Form 3: Load registers. Source + * address is roperand1, first dest register is + * , register count is */ + +#define rST (0x94) /* Form 3: ( + ) = */ +#define rSTI (0xd4) /* Form 3: ( + ( << 2)) = */ +#define rSTH (0x95) /* Form 3: ( + ) = */ +#define rSTIH (0xd5) /* Form 3: ( + ( << 1)) = */ +#define rSTB (0x96) /* Form 3: ( + ) = */ +#define rSTIB (0xd6) /* Form 3: ( + ) = */ + +#define rSTM (0xd7) /* Form 3: Store registers. Destination + * address is roperand1, first source register is + * , register count is */ + +#endif /* __RINSN32_H */ diff --git a/misc/pascal/insn32/libinsn/paddopcode.c b/misc/pascal/insn32/libinsn/paddopcode.c index 247c46e2c..2f873eb7f 100644 --- a/misc/pascal/insn32/libinsn/paddopcode.c +++ b/misc/pascal/insn32/libinsn/paddopcode.c @@ -1,96 +1,99 @@ -/********************************************************************** - * paddopcode - * P-Code access utilities - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include "keywords.h" -#include "podefs.h" -#include "pinsn32.h" - -#include "paslib.h" -#include "pofflib.h" -#include "pinsn.h" - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -/********************************************************************** - * Global Variables - **********************************************************************/ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/********************************************************************** - * Global Functions - **********************************************************************/ - -/**********************************************************************/ - -void insn_AddOpCode(poffHandle_t hProg, OPTYPE *ptr) -{ - /* Handle big-endian byte stream */ - - (void)poffAddProgByte(hProg, ptr->op); - - /* Write the 32-bit argument if present */ - - if (ptr->op & o32) - { - ubyte *pb = (ubyte*)&ptr->arg; - (void)poffAddProgByte(hProg, pb[opB1]); - (void)poffAddProgByte(hProg, pb[opB2]); - (void)poffAddProgByte(hProg, pb[opB3]); - (void)poffAddProgByte(hProg, pb[opB4]); - } -} - -/**********************************************************************/ - -void insn_ResetOpCodeWrite(poffHandle_t hProg) -{ - poffResetAccess(hProg); -} - -/***********************************************************************/ +/********************************************************************** + * paddopcode + * P-Code access utilities + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include + +#include "keywords.h" +#include "podefs.h" +#include "pinsn32.h" + +#include "paslib.h" +#include "pofflib.h" +#include "pinsn.h" + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +/********************************************************************** + * Global Variables + **********************************************************************/ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/********************************************************************** + * Global Functions + **********************************************************************/ + +/**********************************************************************/ + +void insn_AddOpCode(poffHandle_t hProg, OPTYPE *ptr) +{ + /* Handle big-endian byte stream */ + + (void)poffAddProgByte(hProg, ptr->op); + + /* Write the 32-bit argument if present */ + + if (ptr->op & o32) + { + uint8_t *pb = (uint8_t*)&ptr->arg; + + (void)poffAddProgByte(hProg, pb[opB1]); + (void)poffAddProgByte(hProg, pb[opB2]); + (void)poffAddProgByte(hProg, pb[opB3]); + (void)poffAddProgByte(hProg, pb[opB4]); + } +} + +/**********************************************************************/ + +void insn_ResetOpCodeWrite(poffHandle_t hProg) +{ + poffResetAccess(hProg); +} + +/***********************************************************************/ diff --git a/misc/pascal/insn32/libinsn/paddtmpopcode.c b/misc/pascal/insn32/libinsn/paddtmpopcode.c index 3b66521e0..e4e10b458 100644 --- a/misc/pascal/insn32/libinsn/paddtmpopcode.c +++ b/misc/pascal/insn32/libinsn/paddtmpopcode.c @@ -1,97 +1,99 @@ -/********************************************************************** - * paddtmpopcode - * P-Code access utilities - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include "keywords.h" -#include "podefs.h" -#include "pinsn32.h" - -#include "paslib.h" -#include "pofflib.h" -#include "pinsn.h" - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -/********************************************************************** - * Global Variables - **********************************************************************/ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/********************************************************************** - * Global Functions - **********************************************************************/ - -/**********************************************************************/ - -void insn_AddTmpOpCode(poffProgHandle_t hProg, OPTYPE *ptr) -{ - /* Write the opcode which is always present */ - - (void)poffAddTmpProgByte(hProg, ptr->op); - - /* Write the 32-bit argument if present */ - - if (ptr->op & o32) - { - ubyte *pb = (ubyte*)&ptr->arg; - - (void)poffAddTmpProgByte(hProg, pb[opB1]); - (void)poffAddTmpProgByte(hProg, pb[opB2]); - (void)poffAddTmpProgByte(hProg, pb[opB3]); - (void)poffAddTmpProgByte(hProg, pb[opB4]); - } -} - -/**********************************************************************/ - -void insn_ResetTmpOpCodeWrite(poffProgHandle_t hProg) -{ - poffResetProgHandle(hProg); -} - -/***********************************************************************/ +/********************************************************************** + * paddtmpopcode + * P-Code access utilities + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include + +#include "keywords.h" +#include "podefs.h" +#include "pinsn32.h" + +#include "paslib.h" +#include "pofflib.h" +#include "pinsn.h" + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +/********************************************************************** + * Global Variables + **********************************************************************/ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/********************************************************************** + * Global Functions + **********************************************************************/ + +/**********************************************************************/ + +void insn_AddTmpOpCode(poffProgHandle_t hProg, OPTYPE *ptr) +{ + /* Write the opcode which is always present */ + + (void)poffAddTmpProgByte(hProg, ptr->op); + + /* Write the 32-bit argument if present */ + + if (ptr->op & o32) + { + uint8_t *pb = (uint8_t*)&ptr->arg; + + (void)poffAddTmpProgByte(hProg, pb[opB1]); + (void)poffAddTmpProgByte(hProg, pb[opB2]); + (void)poffAddTmpProgByte(hProg, pb[opB3]); + (void)poffAddTmpProgByte(hProg, pb[opB4]); + } +} + +/**********************************************************************/ + +void insn_ResetTmpOpCodeWrite(poffProgHandle_t hProg) +{ + poffResetProgHandle(hProg); +} + +/***********************************************************************/ diff --git a/misc/pascal/insn32/libinsn/pdasm.c b/misc/pascal/insn32/libinsn/pdasm.c index 0db6db932..75d79d7b6 100644 --- a/misc/pascal/insn32/libinsn/pdasm.c +++ b/misc/pascal/insn32/libinsn/pdasm.c @@ -1,429 +1,436 @@ -/********************************************************************** - * pdasm.c - * P-Code Disassembler - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -#include - -#include "keywords.h" -#include "podefs.h" -#include "pinsn32.h" -#include "pfdefs.h" -#include "pxdefs.h" -#include "paslib.h" - -#include "pinsn.h" - -/***********************************************************************/ - -/* These are all the format codes that apply to opcodes with an argument */ - -enum { - SIMPLE = 0, /* No argument */ - HEX, /* Hexadecimal argument */ - DECIMAL, /* Signed Decimal argument (w/shift) */ - UDECIMAL, /* Unsigned Decimal argument (w/shift) */ - LABEL_DEC, /* Label number */ - xOP, lbOP, fpOP, /* Sub opcode */ - FILENO, LINENO /* File number, line number */ -}; - -/* The following table defines everything that is needed to disassemble - * a P-Code. NOTE: The order of definition in this table must exactly - * match the declaration sequence in pinsn.h. */ - -static const char invOp[] = "Invalid Opcode"; -struct optab_s -{ - const char *opName; /* Opcode mnemonics */ - ubyte format; /* arg16 format */ -}; - -/******************** OPCODES WITH NO ARGUMENTS *************************/ - -static const struct optab_s g_sNoArgOpTable[64] = -{ - /* Program control (No stack arguments) */ - - /* 0x00 */ { "NOP ", SIMPLE }, - - /* Arithmetic & logical & and integer conversions (One stack argument) */ - - /* 0x01 */ { "NEG ", SIMPLE }, - /* 0x02 */ { "ABS ", SIMPLE }, - /* 0x03 */ { "INC ", SIMPLE }, - /* 0x04 */ { "DEC ", SIMPLE }, - /* 0x05 */ { "NOT ", SIMPLE }, - - /* Arithmetic & logical (Two stack arguments) */ - - /* 0x06 */ { "ADD ", SIMPLE }, - /* 0x07 */ { "SUB ", SIMPLE }, - /* 0x08 */ { "MUL ", SIMPLE }, - /* 0x09 */ { "DIV ", SIMPLE }, - /* 0x0a */ { "MOD ", SIMPLE }, - /* 0x0b */ { "SLL ", SIMPLE }, - /* 0x0c */ { "SRL ", SIMPLE }, - /* 0x0d */ { "SRA ", SIMPLE }, - /* 0x0e */ { "OR ", SIMPLE }, - /* 0x0f */ { "AND ", SIMPLE }, - - /* Comparisons (One stack argument) */ - - /* 0x10 */ { "EQUZ ", SIMPLE }, - /* 0x11 */ { "NEQZ ", SIMPLE }, - /* 0x12 */ { "LTZ ", SIMPLE }, - /* 0x13 */ { "GTEZ ", SIMPLE }, - /* 0x14 */ { "GTZ ", SIMPLE }, - /* 0x15 */ { "LTEZ ", SIMPLE }, - /* 0x16 */ { invOp, SIMPLE }, - /* 0x17 */ { invOp, SIMPLE }, - - /* Comparisons (Two stack arguments) */ - - /* 0x18 */ { "EQU ", SIMPLE }, - /* 0x19 */ { "NEQ ", SIMPLE }, - /* 0x1a */ { "LT ", SIMPLE }, - /* 0x1b */ { "GTE ", SIMPLE }, - /* 0x1c */ { "GT ", SIMPLE }, - /* 0x1d */ { "LTE ", SIMPLE }, - /* 0x1e */ { invOp, SIMPLE }, - /* 0x1f */ { "BIT ", SIMPLE }, - - /* Load (One) or Store (Two stack argument) */ - - /* 0x20 */ { "LDI ", SIMPLE }, - /* 0x21 */ { "LDIH", SIMPLE }, - /* 0x22 */ { "LDIB", SIMPLE }, - /* 0x23 */ { "LDIM", SIMPLE }, - /* 0x24 */ { "STI ", SIMPLE }, - /* 0x25 */ { "STIH", SIMPLE }, - /* 0x26 */ { "STIB", SIMPLE }, - /* 0x27 */ { "STIM", SIMPLE }, - - /* Data stack operations */ - - /* 0x28 */ { "DUP ", SIMPLE }, - /* 0x29 */ { "DUPH ", SIMPLE }, - /* 0x2a */ { "PUSHS", SIMPLE }, - /* 0x2b */ { "POPS", SIMPLE }, - /* 0x2c */ { invOp, SIMPLE }, - /* 0x2d */ { invOp, SIMPLE }, - /* 0x2e */ { invOp, SIMPLE }, - /* 0x2f */ { "RET ", SIMPLE }, - - /* 0x30 */ { invOp, SIMPLE }, - /* 0x31 */ { invOp, SIMPLE }, - /* 0x32 */ { invOp, SIMPLE }, - /* 0x33 */ { invOp, SIMPLE }, - /* 0x34 */ { invOp, SIMPLE }, - /* 0x35 */ { invOp, SIMPLE }, - /* 0x36 */ { invOp, SIMPLE }, - /* 0x37 */ { invOp, SIMPLE }, - - /* System Functions (No stack arguments) */ - - /* 0x38 */ { invOp, SIMPLE }, - /* 0x39 */ { invOp, SIMPLE }, - /* 0x3a */ { invOp, SIMPLE }, - /* 0x3b */ { invOp, SIMPLE }, - /* 0x3c */ { invOp, SIMPLE }, - /* 0x3d */ { invOp, SIMPLE }, - /* 0x3e */ { invOp, SIMPLE }, - /* 0x3f */ { "EXIT ", SIMPLE } -}; - -/****************** OPCODES WITH 25-BIT ARGUMENT ************************/ - -static const struct optab_s g_sArg32OpTable[64] = -{ - /* Load: arg = unsigned base offset */ - - /* 0x80 */ { "LD ", UDECIMAL }, /* No stack arguments */ - /* 0x81 */ { "LDH ", UDECIMAL }, /* No stack arguments */ - /* 0x82 */ { "LDB ", UDECIMAL }, /* No stack arguments */ - /* 0x83 */ { "LDM ", UDECIMAL }, /* One 32-bit stack argument */ - - /* Store: arg = unsigned base offset (One stack arguments) */ - - /* 0x84 */ { "ST ", UDECIMAL }, /* One 32-bit stack argument */ - /* 0x85 */ { "STH ", UDECIMAL }, /* One 32-bit stack argument */ - /* 0x86 */ { "STB ", UDECIMAL }, /* One 32-bit stack argument */ - /* 0x87 */ { "STM ", UDECIMAL }, /* One+n 32-bit stack argument */ - - /* Load Indexed: arg = unsigned base offset */ - - /* 0x88 */ { "LDX ", UDECIMAL }, /* One 32-bit stack argument */ - /* 0x89 */ { "LDXH ", UDECIMAL }, /* One 32-bit stack argument */ - /* 0x8a */ { "LDXB ", UDECIMAL }, /* One 32-bit stack argument */ - /* 0x8b */ { "LDXM ", UDECIMAL }, /* Two 32-bit stack argument */ - - /* Store Indexed: arg = unsigned base offset */ - - /* 0x8c */ { "STX ", UDECIMAL }, /* Two 32-bit stack argument */ - /* 0x8d */ { "STXH ", UDECIMAL }, /* Two 32-bit stack argument */ - /* 0x8e */ { "STXB ", UDECIMAL }, /* Two 32-bit stack argument */ - /* 0x8f */ { "STXM ", UDECIMAL }, /* Two+n 32-bit stack argument */ - - /* Program control: arg = unsigned label (One stack argument) */ - - /* 0x90 */ { "JEQUZ", HEX }, - /* 0x91 */ { "JNEQZ", HEX }, - /* 0x92 */ { "JLTZ ", HEX }, - /* 0x93 */ { "JGTEZ", HEX }, - /* 0x94 */ { "JGTZ ", HEX }, - /* 0x95 */ { "JLTEZ", HEX }, - - /* Program control: arg = unsigned label (no stack arguments) */ - - /* 0x96 */ { "JMP ", HEX }, - /* 0x97 */ { "PUSH ", DECIMAL }, - - /* Program control: arg = unsigned label (One stack argument) */ - - /* 0x98 */ { "JEQU ", HEX }, - /* 0x99 */ { "JNEQ ", HEX }, - /* 0x9a */ { "JLT ", HEX }, - /* 0x9b */ { "JGTE ", HEX }, - /* 0x9c */ { "JGT ", HEX }, - /* 0x9d */ { "JLTE ", HEX }, - /* 0x9e */ { invOp, SIMPLE }, - /* 0x9f */ { "INDS ", DECIMAL }, - - /* Load: Uses LSP; arg = signed frame offset */ - - /* 0xa0 */ { "LDS ", DECIMAL }, /* No stack arguments */ - /* 0xa1 */ { "LDSH ", DECIMAL }, /* No stack arguments */ - /* 0xa2 */ { "LDSB ", DECIMAL }, /* No stack arguments */ - /* 0xa3 */ { "LDSM ", DECIMAL }, /* One 32-bit stack argument */ - - /* Store: Uses LSP; arg = signed frame offset */ - - /* 0xa4 */ { "STS ", DECIMAL }, /* One 32-bit stack argument */ - /* 0xa5 */ { "STSH ", DECIMAL }, /* One 32-bit stack argument */ - /* 0xa6 */ { "STSB ", DECIMAL }, /* One 32-bit stack argument */ - /* 0xa7 */ { "STSM ", DECIMAL }, /* One+n 32-bit stack argument */ - - /* Load Indexed: Uses LSP; arg = signed frame offset */ - - /* 0xa8 */ { "LDSX ", DECIMAL }, /* One 32-bit stack argument */ - /* 0xa9 */ { "LDSXH", DECIMAL }, /* One 32-bit stack argument */ - /* 0xaa */ { "LDSXB", DECIMAL }, /* One 32-bit stack argument */ - /* 0xab */ { "LDSXM", DECIMAL }, /* Two 32-bit stack argument */ - - /* Store Indexed: Uses LSP; arg = signed frame offset */ - - /* 0xac */ { "STSX ", DECIMAL }, /* Two 32-bit stack argument */ - /* 0xad */ { "STSXH", DECIMAL }, /* Two 32-bit stack argument */ - /* 0xae */ { "STSXB", DECIMAL }, /* Two 32-bit stack argument */ - /* 0xaf */ { "STSXM", DECIMAL }, /* Two+n 32-bit stack argument */ - - /* Load address relative to stack base: arg = unsigned offset */ - - /* 0xb0 */ { "LA ", UDECIMAL }, - - /* Load address: Uses SLP, arg = signed frame offset */ - - /* 0xb1 */ { "LAS ", DECIMAL }, - - /* Load absolute stack address: arg = RODATA offset (No stack arguments) */ - - /* 0xb2 */ { "LAC ", HEX, }, - /* 0xb3 */ { invOp, SIMPLE }, - - /* Load address relative to stack base: arg = unsigned offset, TOS=index */ - - /* 0xb4 */ { "LAX ", UDECIMAL }, - - /* Load address indexed: Uses SLP, arg = signed frame offset */ - - /* 0xb5 */ { "LASX ", DECIMAL }, - - /* Set LSP: arg = new level that evaluates to LSP value */ - - /* 0xb6 */ { "SLSP ", UDECIMAL }, - /* 0xb7 */ { "SDC ", UDECIMAL }, - /* 0xb8 */ { invOp, SIMPLE }, - - /* Program Control: Uses LSP; arg = unsigned label (No stack arguments) */ - - /* 0xb9 */ { "PCAL ", HEX }, - - /* System calls: arg = file number | sub-function code */ - - /* 0xba */ { "SYSIO", xOP }, - - /* System functions: arg = 32-bit library call identifier */ - - /* 0xbb */ { "LIB ", lbOP }, - - /* Floating point operations: arg = FP op-code */ - - /* 0xbc */ { "FLOAT", fpOP }, - - /* Program control: arg = unsigned label (no stack arguments) */ - - /* 0xbd */ { NULL, LABEL_DEC }, - - /* Psuedo-operations: arg = file number OR line number */ - - /* 0xbe */ { "INCLUDE ", FILENO }, - /* 0xbf */ { "LINE ", LINENO }, -}; - -static const char invXOp[] = "Invalid SYSIO"; -static const char *xName[MAX_XOP] = { /* SYSIO opcode mnemonics */ -/* 0x00 */ invXOp, "EOF", "EOLN", "RESET", -/* 0x04 */ "REWRITE", invXOp, invXOp, invXOp, -/* 0x08 */ invXOp, invXOp, invXOp, invXOp, -/* 0x0c */ invXOp, invXOp, invXOp, invXOp, -/* 0x10 */ "READLN", "READPG", "READBIN", "READINT", -/* 0x14 */ "READCHR", "READSTR", "READRL", invXOp, -/* 0x18 */ invXOp, invXOp, invXOp, invXOp, -/* 0x1c */ invXOp, invXOp, invXOp, invXOp, -/* 0x20 */ "WRITELN", "WRITEPG", "WRITEBIN", "WRITEINT", -/* 0x24 */ "WRITECHR", "WRITESTR", "WRITERL" }; - -static const char invLbOp[] = "Invalid runtime code"; -static const char *lbName[MAX_LBOP] = { /* LIB opcode mnemonics */ -/* 0x00 */ "GETENV", "STR2STR", "CSTR2STR", "STR2RSTR", -/* 0x04 */ "CSTR2RSTR", "VAL", "MKSTK", "MKSTKSTR", -/* 0x08 */ "MKSTKC", "STRCAT", "STRCATC", "STRCMP" }; - -#define MAX_FOP 16 -static const char invFpOp[] = "Invalid FP Operation"; -static const char *fpName[MAX_FOP] = { -/* 0x00 */ invFpOp, "FLOAT", "TRUNC", "ROUND", -/* 0x04 */ "NEG", "ADD", "SUB", "MUL", -/* 0x08 */ "DIV", "MOD", "EQU", "NEQ", -/* 0x0c */ "LT", "GTE", "GT", "LTE" }; - -/***********************************************************************/ - -void insn_DisassemblePCode(FILE* lfile, OPTYPE *pop) -{ - const struct optab_s *opTable; - int idx; - - /* Select table based upon whether an opcode is included or not */ - - if (pop->op & o32) - { - opTable = g_sArg32OpTable; - idx = pop->op & ~o32; - } - else - { - opTable = g_sNoArgOpTable; - idx = pop->op; - } - - /* Indent, comment or label as appropriate */ - - switch (opTable[idx].format) - { - case LABEL_DEC : - fprintf(lfile, "L%08lx:\n", pop->arg); - return; - case FILENO : - case LINENO : - fprintf(lfile, "; "); - break; - default : - fprintf(lfile, " "); - } /* end switch */ - - /* Print the opcode mnemonic */ - - fprintf(lfile, "%s ", opTable[idx].opName); - - /* Print the argument (if present) */ - - if (pop->op & o32) - { - switch (opTable[idx].format) - { - case HEX : - fprintf(lfile, "0x%08lx", pop->arg); - break; - - case FILENO : - case LINENO : - case DECIMAL : - fprintf(lfile, "%ld", (sint32)pop->arg); - break; - - case UDECIMAL : - fprintf(lfile, "%1lu", pop->arg); - break; - - case fpOP : - if ((pop->arg & 0x3f) < MAX_FOP) - fprintf(lfile, "%s", fpName[(pop->arg & 0x3f)]); - else - fprintf(lfile, "%s", invFpOp); - break; - - case xOP : - { - unsigned fileno = pop->arg >> 16; - unsigned xop = pop->arg & 0xffff; - fprintf(lfile, "%d, ", fileno); - if (xop < MAX_XOP) - fprintf(lfile, "%s", xName[xop]); - else - fprintf(lfile, "%s", invXOp); - } - break; - - case lbOP : - if (pop->arg < MAX_LBOP) - fprintf(lfile, "%s", lbName[pop->arg]); - else - fprintf(lfile, "%s", invLbOp); - break; - - case LABEL_DEC : - default : - break; - } - } - - /* Don't forget the newline! */ - - fputc('\n', lfile); - -} /* end dissassemblePcode */ - -/***********************************************************************/ +/********************************************************************** + * pdasm.c + * P-Code Disassembler + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include + +#include "keywords.h" +#include "podefs.h" +#include "pinsn32.h" +#include "pfdefs.h" +#include "pxdefs.h" +#include "paslib.h" + +#include "pinsn.h" + +/********************************************************************** + * Private Types + **********************************************************************/ + +/* These are all the format codes that apply to opcodes with an argument */ + +enum { + SIMPLE = 0, /* No argument */ + HEX, /* Hexadecimal argument */ + DECIMAL, /* Signed Decimal argument (w/shift) */ + UDECIMAL, /* Unsigned Decimal argument (w/shift) */ + LABEL_DEC, /* Label number */ + xOP, lbOP, fpOP, /* Sub opcode */ + FILENO, LINENO /* File number, line number */ +}; + +/* The following table defines everything that is needed to disassemble + * a P-Code. NOTE: The order of definition in this table must exactly + * match the declaration sequence in pinsn.h. */ + +static const char invOp[] = "Invalid Opcode"; +struct optab_s +{ + const char *opName; /* Opcode mnemonics */ + uint8_t format; /* arg16 format */ +}; + +/******************** OPCODES WITH NO ARGUMENTS *************************/ + +static const struct optab_s g_sNoArgOpTable[64] = +{ + /* Program control (No stack arguments) */ + + /* 0x00 */ { "NOP ", SIMPLE }, + + /* Arithmetic & logical & and integer conversions (One stack argument) */ + + /* 0x01 */ { "NEG ", SIMPLE }, + /* 0x02 */ { "ABS ", SIMPLE }, + /* 0x03 */ { "INC ", SIMPLE }, + /* 0x04 */ { "DEC ", SIMPLE }, + /* 0x05 */ { "NOT ", SIMPLE }, + + /* Arithmetic & logical (Two stack arguments) */ + + /* 0x06 */ { "ADD ", SIMPLE }, + /* 0x07 */ { "SUB ", SIMPLE }, + /* 0x08 */ { "MUL ", SIMPLE }, + /* 0x09 */ { "DIV ", SIMPLE }, + /* 0x0a */ { "MOD ", SIMPLE }, + /* 0x0b */ { "SLL ", SIMPLE }, + /* 0x0c */ { "SRL ", SIMPLE }, + /* 0x0d */ { "SRA ", SIMPLE }, + /* 0x0e */ { "OR ", SIMPLE }, + /* 0x0f */ { "AND ", SIMPLE }, + + /* Comparisons (One stack argument) */ + + /* 0x10 */ { "EQUZ ", SIMPLE }, + /* 0x11 */ { "NEQZ ", SIMPLE }, + /* 0x12 */ { "LTZ ", SIMPLE }, + /* 0x13 */ { "GTEZ ", SIMPLE }, + /* 0x14 */ { "GTZ ", SIMPLE }, + /* 0x15 */ { "LTEZ ", SIMPLE }, + /* 0x16 */ { invOp, SIMPLE }, + /* 0x17 */ { invOp, SIMPLE }, + + /* Comparisons (Two stack arguments) */ + + /* 0x18 */ { "EQU ", SIMPLE }, + /* 0x19 */ { "NEQ ", SIMPLE }, + /* 0x1a */ { "LT ", SIMPLE }, + /* 0x1b */ { "GTE ", SIMPLE }, + /* 0x1c */ { "GT ", SIMPLE }, + /* 0x1d */ { "LTE ", SIMPLE }, + /* 0x1e */ { invOp, SIMPLE }, + /* 0x1f */ { "BIT ", SIMPLE }, + + /* Load (One) or Store (Two stack argument) */ + + /* 0x20 */ { "LDI ", SIMPLE }, + /* 0x21 */ { "LDIH", SIMPLE }, + /* 0x22 */ { "LDIB", SIMPLE }, + /* 0x23 */ { "LDIM", SIMPLE }, + /* 0x24 */ { "STI ", SIMPLE }, + /* 0x25 */ { "STIH", SIMPLE }, + /* 0x26 */ { "STIB", SIMPLE }, + /* 0x27 */ { "STIM", SIMPLE }, + + /* Data stack operations */ + + /* 0x28 */ { "DUP ", SIMPLE }, + /* 0x29 */ { "DUPH ", SIMPLE }, + /* 0x2a */ { "PUSHS", SIMPLE }, + /* 0x2b */ { "POPS", SIMPLE }, + /* 0x2c */ { invOp, SIMPLE }, + /* 0x2d */ { invOp, SIMPLE }, + /* 0x2e */ { invOp, SIMPLE }, + /* 0x2f */ { "RET ", SIMPLE }, + + /* 0x30 */ { invOp, SIMPLE }, + /* 0x31 */ { invOp, SIMPLE }, + /* 0x32 */ { invOp, SIMPLE }, + /* 0x33 */ { invOp, SIMPLE }, + /* 0x34 */ { invOp, SIMPLE }, + /* 0x35 */ { invOp, SIMPLE }, + /* 0x36 */ { invOp, SIMPLE }, + /* 0x37 */ { invOp, SIMPLE }, + + /* System Functions (No stack arguments) */ + + /* 0x38 */ { invOp, SIMPLE }, + /* 0x39 */ { invOp, SIMPLE }, + /* 0x3a */ { invOp, SIMPLE }, + /* 0x3b */ { invOp, SIMPLE }, + /* 0x3c */ { invOp, SIMPLE }, + /* 0x3d */ { invOp, SIMPLE }, + /* 0x3e */ { invOp, SIMPLE }, + /* 0x3f */ { "EXIT ", SIMPLE } +}; + +/****************** OPCODES WITH 25-BIT ARGUMENT ************************/ + +static const struct optab_s g_sArg32OpTable[64] = +{ + /* Load: arg = unsigned base offset */ + + /* 0x80 */ { "LD ", UDECIMAL }, /* No stack arguments */ + /* 0x81 */ { "LDH ", UDECIMAL }, /* No stack arguments */ + /* 0x82 */ { "LDB ", UDECIMAL }, /* No stack arguments */ + /* 0x83 */ { "LDM ", UDECIMAL }, /* One 32-bit stack argument */ + + /* Store: arg = unsigned base offset (One stack arguments) */ + + /* 0x84 */ { "ST ", UDECIMAL }, /* One 32-bit stack argument */ + /* 0x85 */ { "STH ", UDECIMAL }, /* One 32-bit stack argument */ + /* 0x86 */ { "STB ", UDECIMAL }, /* One 32-bit stack argument */ + /* 0x87 */ { "STM ", UDECIMAL }, /* One+n 32-bit stack argument */ + + /* Load Indexed: arg = unsigned base offset */ + + /* 0x88 */ { "LDX ", UDECIMAL }, /* One 32-bit stack argument */ + /* 0x89 */ { "LDXH ", UDECIMAL }, /* One 32-bit stack argument */ + /* 0x8a */ { "LDXB ", UDECIMAL }, /* One 32-bit stack argument */ + /* 0x8b */ { "LDXM ", UDECIMAL }, /* Two 32-bit stack argument */ + + /* Store Indexed: arg = unsigned base offset */ + + /* 0x8c */ { "STX ", UDECIMAL }, /* Two 32-bit stack argument */ + /* 0x8d */ { "STXH ", UDECIMAL }, /* Two 32-bit stack argument */ + /* 0x8e */ { "STXB ", UDECIMAL }, /* Two 32-bit stack argument */ + /* 0x8f */ { "STXM ", UDECIMAL }, /* Two+n 32-bit stack argument */ + + /* Program control: arg = unsigned label (One stack argument) */ + + /* 0x90 */ { "JEQUZ", HEX }, + /* 0x91 */ { "JNEQZ", HEX }, + /* 0x92 */ { "JLTZ ", HEX }, + /* 0x93 */ { "JGTEZ", HEX }, + /* 0x94 */ { "JGTZ ", HEX }, + /* 0x95 */ { "JLTEZ", HEX }, + + /* Program control: arg = unsigned label (no stack arguments) */ + + /* 0x96 */ { "JMP ", HEX }, + /* 0x97 */ { "PUSH ", DECIMAL }, + + /* Program control: arg = unsigned label (One stack argument) */ + + /* 0x98 */ { "JEQU ", HEX }, + /* 0x99 */ { "JNEQ ", HEX }, + /* 0x9a */ { "JLT ", HEX }, + /* 0x9b */ { "JGTE ", HEX }, + /* 0x9c */ { "JGT ", HEX }, + /* 0x9d */ { "JLTE ", HEX }, + /* 0x9e */ { invOp, SIMPLE }, + /* 0x9f */ { "INDS ", DECIMAL }, + + /* Load: Uses LSP; arg = signed frame offset */ + + /* 0xa0 */ { "LDS ", DECIMAL }, /* No stack arguments */ + /* 0xa1 */ { "LDSH ", DECIMAL }, /* No stack arguments */ + /* 0xa2 */ { "LDSB ", DECIMAL }, /* No stack arguments */ + /* 0xa3 */ { "LDSM ", DECIMAL }, /* One 32-bit stack argument */ + + /* Store: Uses LSP; arg = signed frame offset */ + + /* 0xa4 */ { "STS ", DECIMAL }, /* One 32-bit stack argument */ + /* 0xa5 */ { "STSH ", DECIMAL }, /* One 32-bit stack argument */ + /* 0xa6 */ { "STSB ", DECIMAL }, /* One 32-bit stack argument */ + /* 0xa7 */ { "STSM ", DECIMAL }, /* One+n 32-bit stack argument */ + + /* Load Indexed: Uses LSP; arg = signed frame offset */ + + /* 0xa8 */ { "LDSX ", DECIMAL }, /* One 32-bit stack argument */ + /* 0xa9 */ { "LDSXH", DECIMAL }, /* One 32-bit stack argument */ + /* 0xaa */ { "LDSXB", DECIMAL }, /* One 32-bit stack argument */ + /* 0xab */ { "LDSXM", DECIMAL }, /* Two 32-bit stack argument */ + + /* Store Indexed: Uses LSP; arg = signed frame offset */ + + /* 0xac */ { "STSX ", DECIMAL }, /* Two 32-bit stack argument */ + /* 0xad */ { "STSXH", DECIMAL }, /* Two 32-bit stack argument */ + /* 0xae */ { "STSXB", DECIMAL }, /* Two 32-bit stack argument */ + /* 0xaf */ { "STSXM", DECIMAL }, /* Two+n 32-bit stack argument */ + + /* Load address relative to stack base: arg = unsigned offset */ + + /* 0xb0 */ { "LA ", UDECIMAL }, + + /* Load address: Uses SLP, arg = signed frame offset */ + + /* 0xb1 */ { "LAS ", DECIMAL }, + + /* Load absolute stack address: arg = RODATA offset (No stack arguments) */ + + /* 0xb2 */ { "LAC ", HEX, }, + /* 0xb3 */ { invOp, SIMPLE }, + + /* Load address relative to stack base: arg = unsigned offset, TOS=index */ + + /* 0xb4 */ { "LAX ", UDECIMAL }, + + /* Load address indexed: Uses SLP, arg = signed frame offset */ + + /* 0xb5 */ { "LASX ", DECIMAL }, + + /* Set LSP: arg = new level that evaluates to LSP value */ + + /* 0xb6 */ { "SLSP ", UDECIMAL }, + /* 0xb7 */ { "SDC ", UDECIMAL }, + /* 0xb8 */ { invOp, SIMPLE }, + + /* Program Control: Uses LSP; arg = unsigned label (No stack arguments) */ + + /* 0xb9 */ { "PCAL ", HEX }, + + /* System calls: arg = file number | sub-function code */ + + /* 0xba */ { "SYSIO", xOP }, + + /* System functions: arg = 32-bit library call identifier */ + + /* 0xbb */ { "LIB ", lbOP }, + + /* Floating point operations: arg = FP op-code */ + + /* 0xbc */ { "FLOAT", fpOP }, + + /* Program control: arg = unsigned label (no stack arguments) */ + + /* 0xbd */ { NULL, LABEL_DEC }, + + /* Psuedo-operations: arg = file number OR line number */ + + /* 0xbe */ { "INCLUDE ", FILENO }, + /* 0xbf */ { "LINE ", LINENO }, +}; + +static const char invXOp[] = "Invalid SYSIO"; +static const char *xName[MAX_XOP] = { /* SYSIO opcode mnemonics */ +/* 0x00 */ invXOp, "EOF", "EOLN", "RESET", +/* 0x04 */ "REWRITE", invXOp, invXOp, invXOp, +/* 0x08 */ invXOp, invXOp, invXOp, invXOp, +/* 0x0c */ invXOp, invXOp, invXOp, invXOp, +/* 0x10 */ "READLN", "READPG", "READBIN", "READINT", +/* 0x14 */ "READCHR", "READSTR", "READRL", invXOp, +/* 0x18 */ invXOp, invXOp, invXOp, invXOp, +/* 0x1c */ invXOp, invXOp, invXOp, invXOp, +/* 0x20 */ "WRITELN", "WRITEPG", "WRITEBIN", "WRITEINT", +/* 0x24 */ "WRITECHR", "WRITESTR", "WRITERL" }; + +static const char invLbOp[] = "Invalid runtime code"; +static const char *lbName[MAX_LBOP] = { /* LIB opcode mnemonics */ +/* 0x00 */ "GETENV", "STR2STR", "CSTR2STR", "STR2RSTR", +/* 0x04 */ "CSTR2RSTR", "VAL", "MKSTK", "MKSTKSTR", +/* 0x08 */ "MKSTKC", "STRCAT", "STRCATC", "STRCMP" }; + +#define MAX_FOP 16 +static const char invFpOp[] = "Invalid FP Operation"; +static const char *fpName[MAX_FOP] = { +/* 0x00 */ invFpOp, "FLOAT", "TRUNC", "ROUND", +/* 0x04 */ "NEG", "ADD", "SUB", "MUL", +/* 0x08 */ "DIV", "MOD", "EQU", "NEQ", +/* 0x0c */ "LT", "GTE", "GT", "LTE" }; + +/***********************************************************************/ + +void insn_DisassemblePCode(FILE* lfile, OPTYPE *pop) +{ + const struct optab_s *opTable; + int idx; + + /* Select table based upon whether an opcode is included or not */ + + if (pop->op & o32) + { + opTable = g_sArg32OpTable; + idx = pop->op & ~o32; + } + else + { + opTable = g_sNoArgOpTable; + idx = pop->op; + } + + /* Indent, comment or label as appropriate */ + + switch (opTable[idx].format) + { + case LABEL_DEC : + fprintf(lfile, "L%08lx:\n", pop->arg); + return; + case FILENO : + case LINENO : + fprintf(lfile, "; "); + break; + default : + fprintf(lfile, " "); + } /* end switch */ + + /* Print the opcode mnemonic */ + + fprintf(lfile, "%s ", opTable[idx].opName); + + /* Print the argument (if present) */ + + if (pop->op & o32) + { + switch (opTable[idx].format) + { + case HEX : + fprintf(lfile, "0x%08lx", pop->arg); + break; + + case FILENO : + case LINENO : + case DECIMAL : + fprintf(lfile, "%ld", (int32_t)pop->arg); + break; + + case UDECIMAL : + fprintf(lfile, "%1lu", pop->arg); + break; + + case fpOP : + if ((pop->arg & 0x3f) < MAX_FOP) + fprintf(lfile, "%s", fpName[(pop->arg & 0x3f)]); + else + fprintf(lfile, "%s", invFpOp); + break; + + case xOP : + { + unsigned fileno = pop->arg >> 16; + unsigned xop = pop->arg & 0xffff; + fprintf(lfile, "%d, ", fileno); + if (xop < MAX_XOP) + fprintf(lfile, "%s", xName[xop]); + else + fprintf(lfile, "%s", invXOp); + } + break; + + case lbOP : + if (pop->arg < MAX_LBOP) + fprintf(lfile, "%s", lbName[pop->arg]); + else + fprintf(lfile, "%s", invLbOp); + break; + + case LABEL_DEC : + default : + break; + } + } + + /* Don't forget the newline! */ + + fputc('\n', lfile); + +} /* end dissassemblePcode */ + +/***********************************************************************/ diff --git a/misc/pascal/insn32/libinsn/pgen.c b/misc/pascal/insn32/libinsn/pgen.c index d6584147d..a3219d388 100644 --- a/misc/pascal/insn32/libinsn/pgen.c +++ b/misc/pascal/insn32/libinsn/pgen.c @@ -1,382 +1,383 @@ -/********************************************************************** - * pgen.c - * P-Code generation logic - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include -#include -#include - -#include "config.h" /* Configuration */ -#include "keywords.h" /* Standard types */ -#include "pdefs.h" /* Common types */ -#include "pofflib.h" /* POFF library definitions */ -#include "podefs.h" /* Logical opcode definitions */ -#include "pedefs.h" /* Error codes */ -#include "pinsn32.h" /* 32-bit target INSN opcode definitions */ -#include "perr.h" /* Error handling logic */ - -#include "pinsn.h" /* (to verify prototypes in this file) */ - -/********************************************************************** - * Definitions - **********************************************************************/ - -#define INVALID_INCLUDE (-1) - -/********************************************************************** - * Global Variables - **********************************************************************/ - -extern poffHandle_t poffHandle; /* Handle to POFF object */ -extern FILE *lstFile; /* LIST file pointer */ -extern sint16 level; /* Static nesting level */ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -static const ubyte opmap[NUM_OPCODES] = -{ - oNOP, /* opNOP */ - oNEG, /* opNEG */ - oABS, /* opABS */ - oINC, /* opINC */ - oDEC, /* opDEC */ - oNOT, /* opNOT */ - oADD, /* opADD */ - oSUB, /* opSUB */ - oMUL, /* opMUL */ - oDIV, /* opDIV */ - oMOD, /* opMOD */ - oSLL, /* opSLL */ - oSRL, /* opSRL */ - oSRA, /* opSRA */ - oOR, /* opOR */ - oAND, /* opAND */ - oEQUZ, /* opEQUZ */ - oNEQZ, /* opNEQZ */ - oLTZ, /* opLTZ */ - oGTEZ, /* opGTEZ */ - oGTZ, /* opGTZ */ - oLTEZ, /* opLTEZ */ - oEQU, /* opEQU */ - oNEQ, /* opNEQ */ - oLT, /* opLT */ - oGTE, /* opGTE */ - oGT, /* opGT */ - oLTE, /* opLTE */ - oBIT, /* opBIT */ - oLDI, /* opLDI */ - oLDIB, /* opLDIB */ - oLDIM, /* opLDIM */ - oSTI, /* opSTI */ - oSTIB, /* opSTIB */ - oSTIM, /* opSTIM */ - oDUP, /* opDUP */ - oPUSHS, /* opPUSHS */ - oPOPS, /* opPOPS */ - oRET, /* opRET */ - oEND, /* opEND */ - oFLOAT, /* opFLOAT */ - oJEQUZ, /* opJEQUZ */ - oJNEQZ, /* opJNEQZ */ - oJMP, /* opJMP */ - oJEQU, /* opJEQU */ - oJNEQ, /* opJNEQ */ - oJLT, /* opJLT */ - oJGTE, /* opJGTE */ - oJGT, /* opJGT */ - oJLTE, /* opJLTE */ - oLD, /* opLD */ - oLDH, /* opLDH */ - oLDB, /* opLDB */ - oLDM, /* opLDM */ - oST, /* opST */ - oSTB, /* opSTB */ - oSTM, /* opSTM */ - oLDX, /* opLDX */ - oLDXB, /* opLDXB */ - oLDXM, /* opLDXM */ - oSTX, /* opSTX */ - oSTXB, /* opSTXB */ - oSTXM, /* opSTXM */ - oLA, /* opLA */ - oLAC, /* opLAC */ - oPUSH, /* opPUSH */ - oINDS, /* opINDS */ - oLAX, /* opLAX */ - oLIB, /* opLIB */ - oLABEL, /* opLABEL */ - oPCAL, /* opPCAL */ - oLDS, /* opLDS */ - oLDSH, /* opLDSH */ - oLDSB, /* opLDSB */ - oLDSM, /* opLDSM */ - oSTS, /* opSTS */ - oSTSB, /* opSTSB */ - oSTSM, /* opSTSM */ - oLDSX, /* opLDSX */ - oLDSXB, /* opLDSXB */ - oLDSXM, /* opLDSXM */ - oSTSX, /* opSTSX */ - oSTSXB, /* opSTSXB */ - oSTSXM, /* opSTSXM */ - oLAS, /* opLAS */ - oLASX, /* opLASX */ - oSYSIO, /* opSYSIO */ - oLINE, /* opLINE */ -}; - -static uint16 g_nCurrentIncludeNumber = INVALID_INCLUDE; - -/*********************************************************************** - * Private Function Prototypes - ***********************************************************************/ - -/*********************************************************************** - * Private Functions - ***********************************************************************/ - -static void -insn32_GenerateSimple(ubyte opcode); -static void -insn32_GenerateDataOperation(ubyte opcode, uint32 data); -static void -insn32_Generate(enum pcode_e opcode, uint32 arg); - -/*********************************************************************** - * Private Functions - ***********************************************************************/ - -/***********************************************************************/ -/* Disassemble an Op-code */ - -#if CONFIG_DEBUG -static inline void -insn32_DisassemblePCode(ubyte opcode, uint32 arg) -{ - OPTYPE op; - - op.op = opcode; - op.arg = arg; - - insn_DisassemblePCode(lstFile, &op); -} -#else -# define insn32_DisassemblePCode(op,a) -#endif - -/***********************************************************************/ -static inline void -insn32_DisassembleOpcode(ubyte opcode, uint32 data) -{ -#if CONFIG_DEBUG - OPTYPE op; - op.op = opcode; - op.arg = data; - insn32_DisassemblePCode(opcode, 0); -#endif -} - -/***********************************************************************/ -/* Generate an Op-Code */ - -static void -insn32_GenerateSimple(ubyte opcode) -{ - TRACE(lstFile,"[insn32_GenerateSimple:0x%02x]", opcode); - - /* Write the 8-bit opcode */ - - poffAddProgByte(poffHandle, opcode); - - /* Now, add the disassembled PCode to the list file. */ - - insn32_DisassembleOpcode(opcode, 0); -} - -/***********************************************************************/ - -static void -insn32_GenerateDataOperation(ubyte opcode, uint32 data) -{ - union - { - ubyte b[4]; - uint32 w; - } udata; - - TRACE(lstFile,"[insn32_GenerateDataOperation:0x%02x:0x%07x]", opcode, data); - - /* Write the 8-bit opcode */ - - poffAddProgByte(poffHandle, opcode); - - /* Write the 32-bit opcode */ - - udata.w = data; - (void)poffAddProgByte(poffHandle, udata.b[opB1]); - (void)poffAddProgByte(poffHandle, udata.b[opB2]); - (void)poffAddProgByte(poffHandle, udata.b[opB3]); - (void)poffAddProgByte(poffHandle, udata.b[opB4]); - - /* Now, add the disassembled PCode to the list file. */ - - insn32_DisassembleOpcode(opcode, data); -} - -/***********************************************************************/ - -static void -insn32_Generate(enum pcode_e opcode, uint32 arg) -{ - ubyte insn_opcode = opmap[opcode]; - - TRACE(lstFile,"[insn32_Generate:0x%02x->0x%02x]", opcode, insn_opcode); - - if (insn_opcode & o32) - { - insn32_GenerateDataOperation(insn_opcode, arg); - } - else - { - insn32_GenerateSimple(insn_opcode); - - /* We ignore the argument... what if one was provided? */ - - if (arg != 0) - { - warn(eARGIGNORED); - } - } -} - -/*********************************************************************** - * Public Functions - ***********************************************************************/ - -void -insn_GenerateSimple(enum pcode_e opcode) -{ - insn32_Generate(opcode, 0); -} - -/***********************************************************************/ - -void -insn_GenerateDataOperation(enum pcode_e opcode, sint32 data) -{ - insn32_Generate(opcode, (uint32)data); -} - -/***********************************************************************/ -/* Data size for the next multiple register operation (in bytes) is - * retained in the DC register. - */ - -void insn_GenerateDataSize(uint32 dwDataSize) -{ - insn32_GenerateDataOperation(oSDC, dwDataSize); -} - -/***********************************************************************/ - -void -insn_GenerateFpOperation(ubyte fpOpcode) -{ - insn32_GenerateDataOperation(oFLOAT, fpOpcode); -} - -/***********************************************************************/ - -void -insn_GenerateIoOperation(uint16 ioOpcode, uint16 fileNumber) -{ - uint32 arg = (uint32)fileNumber << 16 | (uint32)ioOpcode; - insn32_GenerateDataOperation(oSYSIO, arg); -} - -/***********************************************************************/ - -void -insn_BuiltInFunctionCall(uint16 libOpcode) -{ - insn32_GenerateDataOperation(oLIB, (uint32)libOpcode); -} - -/***********************************************************************/ - -void -insn_GenerateLevelReference(enum pcode_e opcode, uint16 level, sint32 offset) -{ - /* Note that level is ignored. We used the level set by the - * preceding call to insn_SetStackLevel(). - */ - - insn32_Generate(opcode, (uint32)offset); -} - -/***********************************************************************/ - -void -insn_GenerateProcedureCall(uint16 level, sint32 offset) -{ - insn32_GenerateDataOperation(oPCAL, (uint32)offset); -} - -/***********************************************************************/ - -void -insn_GenerateLineNumber(uint16 includeNumber, uint32 lineNumber) -{ - if (includeNumber != g_nCurrentIncludeNumber) - { - g_nCurrentIncludeNumber = includeNumber; - insn32_GenerateDataOperation(oINCLUDE, includeNumber); - } - insn32_GenerateDataOperation(oLINE, lineNumber); -} - -/***********************************************************************/ - -void -insn_SetStackLevel(uint32 level) -{ - insn32_GenerateDataOperation(oSLSP, level); -} +/********************************************************************** + * pgen.c + * P-Code generation logic + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include +#include +#include + +#include "config.h" /* Configuration */ +#include "keywords.h" /* Standard types */ +#include "pdefs.h" /* Common types */ +#include "pofflib.h" /* POFF library definitions */ +#include "podefs.h" /* Logical opcode definitions */ +#include "pedefs.h" /* Error codes */ +#include "pinsn32.h" /* 32-bit target INSN opcode definitions */ +#include "perr.h" /* Error handling logic */ + +#include "pinsn.h" /* (to verify prototypes in this file) */ + +/********************************************************************** + * Definitions + **********************************************************************/ + +#define INVALID_INCLUDE (-1) + +/********************************************************************** + * Global Variables + **********************************************************************/ + +extern poffHandle_t poffHandle; /* Handle to POFF object */ +extern FILE *lstFile; /* LIST file pointer */ +extern int16_t level; /* Static nesting level */ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +static const uint8_t opmap[NUM_OPCODES] = +{ + oNOP, /* opNOP */ + oNEG, /* opNEG */ + oABS, /* opABS */ + oINC, /* opINC */ + oDEC, /* opDEC */ + oNOT, /* opNOT */ + oADD, /* opADD */ + oSUB, /* opSUB */ + oMUL, /* opMUL */ + oDIV, /* opDIV */ + oMOD, /* opMOD */ + oSLL, /* opSLL */ + oSRL, /* opSRL */ + oSRA, /* opSRA */ + oOR, /* opOR */ + oAND, /* opAND */ + oEQUZ, /* opEQUZ */ + oNEQZ, /* opNEQZ */ + oLTZ, /* opLTZ */ + oGTEZ, /* opGTEZ */ + oGTZ, /* opGTZ */ + oLTEZ, /* opLTEZ */ + oEQU, /* opEQU */ + oNEQ, /* opNEQ */ + oLT, /* opLT */ + oGTE, /* opGTE */ + oGT, /* opGT */ + oLTE, /* opLTE */ + oBIT, /* opBIT */ + oLDI, /* opLDI */ + oLDIB, /* opLDIB */ + oLDIM, /* opLDIM */ + oSTI, /* opSTI */ + oSTIB, /* opSTIB */ + oSTIM, /* opSTIM */ + oDUP, /* opDUP */ + oPUSHS, /* opPUSHS */ + oPOPS, /* opPOPS */ + oRET, /* opRET */ + oEND, /* opEND */ + oFLOAT, /* opFLOAT */ + oJEQUZ, /* opJEQUZ */ + oJNEQZ, /* opJNEQZ */ + oJMP, /* opJMP */ + oJEQU, /* opJEQU */ + oJNEQ, /* opJNEQ */ + oJLT, /* opJLT */ + oJGTE, /* opJGTE */ + oJGT, /* opJGT */ + oJLTE, /* opJLTE */ + oLD, /* opLD */ + oLDH, /* opLDH */ + oLDB, /* opLDB */ + oLDM, /* opLDM */ + oST, /* opST */ + oSTB, /* opSTB */ + oSTM, /* opSTM */ + oLDX, /* opLDX */ + oLDXB, /* opLDXB */ + oLDXM, /* opLDXM */ + oSTX, /* opSTX */ + oSTXB, /* opSTXB */ + oSTXM, /* opSTXM */ + oLA, /* opLA */ + oLAC, /* opLAC */ + oPUSH, /* opPUSH */ + oINDS, /* opINDS */ + oLAX, /* opLAX */ + oLIB, /* opLIB */ + oLABEL, /* opLABEL */ + oPCAL, /* opPCAL */ + oLDS, /* opLDS */ + oLDSH, /* opLDSH */ + oLDSB, /* opLDSB */ + oLDSM, /* opLDSM */ + oSTS, /* opSTS */ + oSTSB, /* opSTSB */ + oSTSM, /* opSTSM */ + oLDSX, /* opLDSX */ + oLDSXB, /* opLDSXB */ + oLDSXM, /* opLDSXM */ + oSTSX, /* opSTSX */ + oSTSXB, /* opSTSXB */ + oSTSXM, /* opSTSXM */ + oLAS, /* opLAS */ + oLASX, /* opLASX */ + oSYSIO, /* opSYSIO */ + oLINE, /* opLINE */ +}; + +static uint16_t g_nCurrentIncludeNumber = INVALID_INCLUDE; + +/*********************************************************************** + * Private Function Prototypes + ***********************************************************************/ + +/*********************************************************************** + * Private Functions + ***********************************************************************/ + +static void +insn32_GenerateSimple(uint8_t opcode); +static void +insn32_GenerateDataOperation(uint8_t opcode, uint32_t data); +static void +insn32_Generate(enum pcode_e opcode, uint32_t arg); + +/*********************************************************************** + * Private Functions + ***********************************************************************/ + +/***********************************************************************/ +/* Disassemble an Op-code */ + +#if CONFIG_DEBUG +static inline void +insn32_DisassemblePCode(uint8_t opcode, uint32_t arg) +{ + OPTYPE op; + + op.op = opcode; + op.arg = arg; + + insn_DisassemblePCode(lstFile, &op); +} +#else +# define insn32_DisassemblePCode(op,a) +#endif + +/***********************************************************************/ +static inline void +insn32_DisassembleOpcode(uint8_t opcode, uint32_t data) +{ +#if CONFIG_DEBUG + OPTYPE op; + op.op = opcode; + op.arg = data; + insn32_DisassemblePCode(opcode, 0); +#endif +} + +/***********************************************************************/ +/* Generate an Op-Code */ + +static void +insn32_GenerateSimple(uint8_t opcode) +{ + TRACE(lstFile,"[insn32_GenerateSimple:0x%02x]", opcode); + + /* Write the 8-bit opcode */ + + poffAddProgByte(poffHandle, opcode); + + /* Now, add the disassembled PCode to the list file. */ + + insn32_DisassembleOpcode(opcode, 0); +} + +/***********************************************************************/ + +static void +insn32_GenerateDataOperation(uint8_t opcode, uint32_t data) +{ + union + { + uint8_t b[4]; + uint32_t w; + } udata; + + TRACE(lstFile,"[insn32_GenerateDataOperation:0x%02x:0x%07x]", opcode, data); + + /* Write the 8-bit opcode */ + + poffAddProgByte(poffHandle, opcode); + + /* Write the 32-bit opcode */ + + udata.w = data; + (void)poffAddProgByte(poffHandle, udata.b[opB1]); + (void)poffAddProgByte(poffHandle, udata.b[opB2]); + (void)poffAddProgByte(poffHandle, udata.b[opB3]); + (void)poffAddProgByte(poffHandle, udata.b[opB4]); + + /* Now, add the disassembled PCode to the list file. */ + + insn32_DisassembleOpcode(opcode, data); +} + +/***********************************************************************/ + +static void +insn32_Generate(enum pcode_e opcode, uint32_t arg) +{ + uint8_t insn_opcode = opmap[opcode]; + + TRACE(lstFile,"[insn32_Generate:0x%02x->0x%02x]", opcode, insn_opcode); + + if (insn_opcode & o32) + { + insn32_GenerateDataOperation(insn_opcode, arg); + } + else + { + insn32_GenerateSimple(insn_opcode); + + /* We ignore the argument... what if one was provided? */ + + if (arg != 0) + { + warn(eARGIGNORED); + } + } +} + +/*********************************************************************** + * Public Functions + ***********************************************************************/ + +void +insn_GenerateSimple(enum pcode_e opcode) +{ + insn32_Generate(opcode, 0); +} + +/***********************************************************************/ + +void +insn_GenerateDataOperation(enum pcode_e opcode, int32_t data) +{ + insn32_Generate(opcode, (uint32_t)data); +} + +/***********************************************************************/ +/* Data size for the next multiple register operation (in bytes) is + * retained in the DC register. + */ + +void insn_GenerateDataSize(uint32_t dwDataSize) +{ + insn32_GenerateDataOperation(oSDC, dwDataSize); +} + +/***********************************************************************/ + +void +insn_GenerateFpOperation(uint8_t fpOpcode) +{ + insn32_GenerateDataOperation(oFLOAT, fpOpcode); +} + +/***********************************************************************/ + +void +insn_GenerateIoOperation(uint16_t ioOpcode, uint16_t fileNumber) +{ + uint32_t arg = (uint32_t)fileNumber << 16 | (uint32_t)ioOpcode; + insn32_GenerateDataOperation(oSYSIO, arg); +} + +/***********************************************************************/ + +void +insn_BuiltInFunctionCall(uint16_t libOpcode) +{ + insn32_GenerateDataOperation(oLIB, (uint32_t)libOpcode); +} + +/***********************************************************************/ + +void +insn_GenerateLevelReference(enum pcode_e opcode, uint16_t level, int32_t offset) +{ + /* Note that level is ignored. We used the level set by the + * preceding call to insn_SetStackLevel(). + */ + + insn32_Generate(opcode, (uint32_t)offset); +} + +/***********************************************************************/ + +void +insn_GenerateProcedureCall(uint16_t level, int32_t offset) +{ + insn32_GenerateDataOperation(oPCAL, (uint32_t)offset); +} + +/***********************************************************************/ + +void +insn_GenerateLineNumber(uint16_t includeNumber, uint32_t lineNumber) +{ + if (includeNumber != g_nCurrentIncludeNumber) + { + g_nCurrentIncludeNumber = includeNumber; + insn32_GenerateDataOperation(oINCLUDE, includeNumber); + } + insn32_GenerateDataOperation(oLINE, lineNumber); +} + +/***********************************************************************/ + +void +insn_SetStackLevel(uint32_t level) +{ + insn32_GenerateDataOperation(oSLSP, level); +} diff --git a/misc/pascal/insn32/libinsn/pgetopcode.c b/misc/pascal/insn32/libinsn/pgetopcode.c index 7ccabb5a1..bbcc011e9 100644 --- a/misc/pascal/insn32/libinsn/pgetopcode.c +++ b/misc/pascal/insn32/libinsn/pgetopcode.c @@ -1,126 +1,128 @@ -/********************************************************************** - * pgetopcode.c - * P-Code access utilities - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include "keywords.h" -#include "podefs.h" -#include "pinsn32.h" - -#include "paslib.h" -#include "pofflib.h" -#include "pinsn.h" - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -/********************************************************************** - * Global Variables - **********************************************************************/ - -static sint16 g_bEndIn = 0; /* 1 = oEND pcode or EOF received */ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/********************************************************************** - * Global Functions - **********************************************************************/ - -/**********************************************************************/ - -uint32 insn_GetOpCode(poffHandle_t handle, OPTYPE *ptr) -{ - uint32 opsize = 1; - int c; - - TRACE(stderr, "[insn_GetOpCode]"); - - /* If we are not already at the EOF, read the next character from - * the input stream. - */ - - if (!g_bEndIn) - c = poffGetProgByte(handle); - else - c = EOF; - - /* Check for end of file. We may have previously parsed oEND which - * is a 'logical' end of file for a pascal program (but not a unit) - * or we may be at the physical end of the file wihout encountering - * oEND (typical for a UNIT file). - */ - - if ((g_bEndIn) || (c == EOF)) - { - ptr->op = oEND; - } - else - { - ptr->op = c; - g_bEndIn = (c == oEND); - - if (c & o32) - { - ubyte *pb = (ubyte*)&ptr->arg; - pb[opB1] = poffGetProgByte(handle); - pb[opB2] = poffGetProgByte(handle); - pb[opB3] = poffGetProgByte(handle); - pb[opB4] = poffGetProgByte(handle); - opsize += 4; - } - } - - return opsize; -} - -/**********************************************************************/ - -void insn_ResetOpCodeRead(poffHandle_t handle) -{ - poffResetAccess(handle); - g_bEndIn = 0; -} - -/***********************************************************************/ +/********************************************************************** + * pgetopcode.c + * P-Code access utilities + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include + +#include "keywords.h" +#include "podefs.h" +#include "pinsn32.h" + +#include "paslib.h" +#include "pofflib.h" +#include "pinsn.h" + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +/********************************************************************** + * Global Variables + **********************************************************************/ + +static int16_t g_bEndIn = 0; /* 1 = oEND pcode or EOF received */ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/********************************************************************** + * Global Functions + **********************************************************************/ + +/**********************************************************************/ + +uint32_t insn_GetOpCode(poffHandle_t handle, OPTYPE *ptr) +{ + uint32_t opsize = 1; + int c; + + TRACE(stderr, "[insn_GetOpCode]"); + + /* If we are not already at the EOF, read the next character from + * the input stream. + */ + + if (!g_bEndIn) + c = poffGetProgByte(handle); + else + c = EOF; + + /* Check for end of file. We may have previously parsed oEND which + * is a 'logical' end of file for a pascal program (but not a unit) + * or we may be at the physical end of the file wihout encountering + * oEND (typical for a UNIT file). + */ + + if ((g_bEndIn) || (c == EOF)) + { + ptr->op = oEND; + } + else + { + ptr->op = c; + g_bEndIn = (c == oEND); + + if (c & o32) + { + uint8_t *pb = (uint8_t*)&ptr->arg; + pb[opB1] = poffGetProgByte(handle); + pb[opB2] = poffGetProgByte(handle); + pb[opB3] = poffGetProgByte(handle); + pb[opB4] = poffGetProgByte(handle); + opsize += 4; + } + } + + return opsize; +} + +/**********************************************************************/ + +void insn_ResetOpCodeRead(poffHandle_t handle) +{ + poffResetAccess(handle); + g_bEndIn = 0; +} + +/***********************************************************************/ diff --git a/misc/pascal/insn32/libinsn/preloc.c b/misc/pascal/insn32/libinsn/preloc.c index 6d0b017a4..b752abba5 100644 --- a/misc/pascal/insn32/libinsn/preloc.c +++ b/misc/pascal/insn32/libinsn/preloc.c @@ -1,147 +1,149 @@ -/********************************************************************** - * preloc.c - * Perform P-Code relocations - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include "keywords.h" -#include "pdefs.h" -#include "pedefs.h" -#include "podefs.h" -#include "pinsn32.h" - -#include "pofflib.h" -#include "perr.h" -#include "pinsn.h" - -/********************************************************************** - * Definitions - **********************************************************************/ - -/********************************************************************** - * Private Type Definitions - **********************************************************************/ - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -/********************************************************************** - * Global Variables - **********************************************************************/ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -int insn_Relocate(OPTYPE *op, uint32 pcOffset, uint32 roOffset) -{ - switch (op->op) - { - /* Catch each instruction that references the read-only data - * section. - */ - - case oLAC: - /* Add the offset to the read-only data section */ - - op->arg += roOffset; - break; - - /* Catch each instruction that references the text section - * data via an offset. - */ - - case oPCAL: /* Procedure / Function calls */ - case oJMP: /* Unconditional jump */ - case oJEQUZ: /* Jump on unary comparisons with zero */ - case oJNEQZ: - case oJLTZ: - case oJGTEZ: - case oJGTZ: - case oJLTEZ: - case oJEQU: /* Jump on binary comparisons */ - case oJNEQ: - case oJLT: - case oJGTE: - case oJGT: - case oJLTE: - /* Add the offset to the text section */ - - op->arg += pcOffset; - break; - - /* Return an end of file indication if oEND encountered */ - - case oEND: - return 1; - - /* Otherwise, it is not an interesting opcode */ - default: - break; - } - - /* Return 0 on all opcodes other than oEND */ - - return 0; -} - -/***********************************************************************/ - -void insn_FixupProcedureCall(ubyte *progData, uint32 symValue) -{ - - /* Sanity checking */ - - if (progData[0] != oPCAL) - fatal(ePOFFCONFUSION); - - if (symValue > 0xffff) - fatal(eBADSHORTINT); - - /* Perform the relocation */ - - progData[2] = symValue >> 8; - progData[3] = symValue & 0xff; -} - - -/***********************************************************************/ +/********************************************************************** + * preloc.c + * Perform P-Code relocations + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include + +#include "keywords.h" +#include "pdefs.h" +#include "pedefs.h" +#include "podefs.h" +#include "pinsn32.h" + +#include "pofflib.h" +#include "perr.h" +#include "pinsn.h" + +/********************************************************************** + * Definitions + **********************************************************************/ + +/********************************************************************** + * Private Type Definitions + **********************************************************************/ + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +/********************************************************************** + * Global Variables + **********************************************************************/ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +int insn_Relocate(OPTYPE *op, uint32_t pcOffset, uint32_t roOffset) +{ + switch (op->op) + { + /* Catch each instruction that references the read-only data + * section. + */ + + case oLAC: + /* Add the offset to the read-only data section */ + + op->arg += roOffset; + break; + + /* Catch each instruction that references the text section + * data via an offset. + */ + + case oPCAL: /* Procedure / Function calls */ + case oJMP: /* Unconditional jump */ + case oJEQUZ: /* Jump on unary comparisons with zero */ + case oJNEQZ: + case oJLTZ: + case oJGTEZ: + case oJGTZ: + case oJLTEZ: + case oJEQU: /* Jump on binary comparisons */ + case oJNEQ: + case oJLT: + case oJGTE: + case oJGT: + case oJLTE: + /* Add the offset to the text section */ + + op->arg += pcOffset; + break; + + /* Return an end of file indication if oEND encountered */ + + case oEND: + return 1; + + /* Otherwise, it is not an interesting opcode */ + default: + break; + } + + /* Return 0 on all opcodes other than oEND */ + + return 0; +} + +/***********************************************************************/ + +void insn_FixupProcedureCall(uint8_t *progData, uint32_t symValue) +{ + + /* Sanity checking */ + + if (progData[0] != oPCAL) + fatal(ePOFFCONFUSION); + + if (symValue > 0xffff) + fatal(eBADSHORTINT); + + /* Perform the relocation */ + + progData[2] = symValue >> 8; + progData[3] = symValue & 0xff; +} + + +/***********************************************************************/ diff --git a/misc/pascal/insn32/libinsn/presettmpopcodewrite.c b/misc/pascal/insn32/libinsn/presettmpopcodewrite.c index 3b66521e0..e4e10b458 100644 --- a/misc/pascal/insn32/libinsn/presettmpopcodewrite.c +++ b/misc/pascal/insn32/libinsn/presettmpopcodewrite.c @@ -1,97 +1,99 @@ -/********************************************************************** - * paddtmpopcode - * P-Code access utilities - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include "keywords.h" -#include "podefs.h" -#include "pinsn32.h" - -#include "paslib.h" -#include "pofflib.h" -#include "pinsn.h" - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -/********************************************************************** - * Global Variables - **********************************************************************/ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/********************************************************************** - * Global Functions - **********************************************************************/ - -/**********************************************************************/ - -void insn_AddTmpOpCode(poffProgHandle_t hProg, OPTYPE *ptr) -{ - /* Write the opcode which is always present */ - - (void)poffAddTmpProgByte(hProg, ptr->op); - - /* Write the 32-bit argument if present */ - - if (ptr->op & o32) - { - ubyte *pb = (ubyte*)&ptr->arg; - - (void)poffAddTmpProgByte(hProg, pb[opB1]); - (void)poffAddTmpProgByte(hProg, pb[opB2]); - (void)poffAddTmpProgByte(hProg, pb[opB3]); - (void)poffAddTmpProgByte(hProg, pb[opB4]); - } -} - -/**********************************************************************/ - -void insn_ResetTmpOpCodeWrite(poffProgHandle_t hProg) -{ - poffResetProgHandle(hProg); -} - -/***********************************************************************/ +/********************************************************************** + * paddtmpopcode + * P-Code access utilities + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include + +#include "keywords.h" +#include "podefs.h" +#include "pinsn32.h" + +#include "paslib.h" +#include "pofflib.h" +#include "pinsn.h" + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +/********************************************************************** + * Global Variables + **********************************************************************/ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/********************************************************************** + * Global Functions + **********************************************************************/ + +/**********************************************************************/ + +void insn_AddTmpOpCode(poffProgHandle_t hProg, OPTYPE *ptr) +{ + /* Write the opcode which is always present */ + + (void)poffAddTmpProgByte(hProg, ptr->op); + + /* Write the 32-bit argument if present */ + + if (ptr->op & o32) + { + uint8_t *pb = (uint8_t*)&ptr->arg; + + (void)poffAddTmpProgByte(hProg, pb[opB1]); + (void)poffAddTmpProgByte(hProg, pb[opB2]); + (void)poffAddTmpProgByte(hProg, pb[opB3]); + (void)poffAddTmpProgByte(hProg, pb[opB4]); + } +} + +/**********************************************************************/ + +void insn_ResetTmpOpCodeWrite(poffProgHandle_t hProg) +{ + poffResetProgHandle(hProg); +} + +/***********************************************************************/ diff --git a/misc/pascal/insn32/plist/plist.c b/misc/pascal/insn32/plist/plist.c index 5c9c9bfca..d57e7deb7 100644 --- a/misc/pascal/insn32/plist/plist.c +++ b/misc/pascal/insn32/plist/plist.c @@ -1,387 +1,388 @@ -/********************************************************************** - * plist.c - * POFF file lister - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include -#include -#include -#include -#include - -#define _GNU_SOURCE -#include - -#include "keywords.h" -#include "pdefs.h" -#include "podefs.h" -#include "pinsn32.h" -#include "pedefs.h" - -#include "pofflib.h" - -#include "paslib.h" -#include "pinsn.h" - -/********************************************************************** - * Definitions - **********************************************************************/ - -#define MAX_STRING 80 - -/********************************************************************** - * Private Data - **********************************************************************/ - -static char *poffFileName = NULL; -static int showFileHeader = 0; -static int showSectionHeaders = 0; -static int showSymbols = 0; -static int showRelocs = 0; -static int disassemble = 0; - -/********************************************************************** - * Private Constant Data - **********************************************************************/ - -static const struct option long_options[] = -{ - {"all", 0, NULL, 'a'}, - {"file-header", 0, NULL, 'h'}, - {"section-headers", 0, NULL, 'S'}, - {"symbols", 0, NULL, 's'}, - {"relocs", 0, NULL, 'r'}, - {"disassemble", 0, NULL, 'd'}, - {"help", 0, NULL, 'H'}, - {NULL, 0, NULL, 0} -}; - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -static void showUsage (const char *progname); -static void parseArgs (int argc, char **argv); -static void dumpProgramData (poffHandle_t poffHandle); - -/********************************************************************** - * Global Functions - **********************************************************************/ - -int main (int argc, char *argv[], char *envp[]) -{ - FILE *object; /* Object file pointer */ - poffHandle_t poffHandle; /* Handle for POFF object */ - char fileName[FNAME_SIZE+1]; /* Object file name */ - uint16 errCode; /* See pedefs.h */ - - /* Parse the command line arguments */ - - parseArgs(argc, argv); - - /* Open source POFF file -- Use .o or command line extension, if supplied */ - - (void) extension (poffFileName, "o", fileName, 0); - if (!(object = fopen (fileName, "rb"))) - { - printf ("Error opening %s\n", fileName); - exit (1); - } /* end if */ - - /* Read the POFF file */ - - poffHandle = poffCreateHandle(); - if (poffHandle == NULL) - { - printf ("Could not get POFF handler\n"); - exit (1); - } - - errCode = poffReadFile(poffHandle, object); - if (errCode != eNOERROR) - { - printf ("Could not read POFF file\n"); - exit (1); - } - - /* Dump the File Header */ - - if (showFileHeader) - { - poffDumpFileHeader(poffHandle, stdout); - } - - /* Dump the Section Headers */ - - if (showSectionHeaders) - { - poffDumpSectionHeaders(poffHandle, stdout); - } - - /* Dump the symbol table */ - - if (showSymbols) - { - poffDumpSymbolTable(poffHandle, stdout); - } - - /* Dump the relocation table */ - - if (showRelocs) - { - poffDumpRelocTable(poffHandle, stdout); - } - - /* Dump the program data section -- Main Loop */ - - if (disassemble) - { - dumpProgramData(poffHandle); - } - - /* Close files and release objects */ - - poffDestroyHandle(poffHandle); - (void)fclose(object); - return 0; -} /* end main */ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -static void showUsage(const char *progname) -{ - fprintf(stderr, "Usage:\n"); - fprintf(stderr, " %s [options] \n", - progname); - fprintf(stderr, "options:\n"); - fprintf(stderr, " -a --all Equivalent to: -h -S -s -r -d\n"); - fprintf(stderr, " -h --file-header Display the POFF file header\n"); - fprintf(stderr, " -S --section-headers Display the sections' header\n"); - fprintf(stderr, " -s --symbols Display the symbol table\n"); - fprintf(stderr, " -r --relocs Display the relocations\n"); - fprintf(stderr, " -d --disassemble Display disassembled text\n"); - fprintf(stderr, " -H --help Display this information\n"); - exit(1); -} - -/***********************************************************************/ - -static void parseArgs(int argc, char **argv) -{ - int option_index; - int c; - - /* Check for existence of filename argument */ - - if (argc < 2) - { - fprintf(stderr, "ERROR: POFF filename required\n"); - showUsage(argv[0]); - } /* end if */ - - /* Parse the command line options */ - - do - { - c = getopt_long (argc, argv, "ahSsrdH", - long_options, &option_index); - if (c != -1) - { - switch (c) - { - case 'a' : - showFileHeader = 1; - showSectionHeaders = 1; - showSymbols = 1; - showRelocs = 1; - disassemble = 1; - break; - - case 'h' : - showFileHeader = 1; - break; - - case 'S' : - showSectionHeaders = 1; - break; - - case 's' : - showSymbols = 1; - break; - - case 'r' : - showRelocs = 1; - break; - - case 'd' : - disassemble = 1; - break; - - case 'H' : - showUsage(argv[0]); - break; - - default: - /* Shouldn't happen */ - - fprintf(stderr, "ERROR: Unrecognized option\n"); - showUsage(argv[0]); - } - } - } - while (c != -1); - - /* Get the name of the p-code file(s) from the last argument(s) */ - - if (optind != argc-1) - { - fprintf(stderr, "ERROR: POFF filename required as final argument\n"); - showUsage(argv[0]); - } - - /* Save the POFF file name */ - - poffFileName = argv[argc-1]; -} - -/***********************************************************************/ - -static void dumpProgramData(poffHandle_t poffHandle) -{ - poffLibLineNumber_t *lastln; /* Previous line number reference */ - poffLibLineNumber_t *ln; /* Current line number reference */ - poffLibDebugFuncInfo_t *dfi; /* Current line debug info */ - uint32 pc; /* Program counter */ - int opSize; /* Size of the opcode */ - int inch; /* Input char */ - OPTYPE op; /* opcode */ - - /* Read the line number entries from the POFF file */ - - poffReadLineNumberTable(poffHandle); - - /* Read the debug function information from the POFF file */ - - poffReadDebugFuncInfoTable(poffHandle); - - /* Dump the program data section -- DumpProgramData Loop */ - - pc = 0; - lastln = NULL; - - while ((inch = poffGetProgByte(poffHandle)) != EOF) - { - /* Get opcode arguments (if any) */ - - op.op = inch; - opSize = 1; - - if (inch & o32) - { - uint32 arg; - - /* Handle 32-bits in big endian byte stream */ - - arg = poffGetProgByte(poffHandle) << 24; - arg |= poffGetProgByte(poffHandle) << 16; - arg |= poffGetProgByte(poffHandle) << 8; - arg |= poffGetProgByte(poffHandle); - - op.arg = arg; - opSize += 4; - } - - /* Check for debug information associated with this line */ - - dfi = poffFindDebugFuncInfo(pc); - if (dfi) - { - int i; - if (dfi->retsize) - { - printf("\nFUNCTION ENTRY: return size=%ld nparms=%ld\n", - dfi->retsize, dfi->nparms); - } - else - { - printf("\nPROCEDURE ENTRY: nparms=%ld\n", dfi->nparms); - } - - for (i = 0; i < dfi->nparms; i++) - { - printf("Argument %2d: size=%ld\n", i, dfi->argsize[i]); - } - } - - /* Find the line number associated with this line */ - - ln = poffFindLineNumber(pc); - if ((ln) && (ln != lastln)) - { - /* Print the line number line */ - - printf("\n%s:%ld\n", ln->filename, ln->lineno); - - /* This will suppress reporting the same line number - * repeatedly. - */ - - lastln = ln; - } - - /* Print the address then the opcode on stdout */ - - fprintf(stdout, "%08lx ", pc); - insn_DisassemblePCode(stdout, &op); - - /* Bump the PC to the next address */ - - pc += opSize; - - } /* end while */ - - /* Release buffers associated with line number and debug information */ - - poffReleaseLineNumberTable(); - poffReleaseDebugFuncInfoTable(); - -} /* end dumpProgramData */ - -/***********************************************************************/ +/********************************************************************** + * plist.c + * POFF file lister + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include +#include +#include +#include +#include + +#define _GNU_SOURCE +#include + +#include "keywords.h" +#include "pdefs.h" +#include "podefs.h" +#include "pinsn32.h" +#include "pedefs.h" + +#include "pofflib.h" + +#include "paslib.h" +#include "pinsn.h" + +/********************************************************************** + * Definitions + **********************************************************************/ + +#define MAX_STRING 80 + +/********************************************************************** + * Private Data + **********************************************************************/ + +static char *poffFileName = NULL; +static int showFileHeader = 0; +static int showSectionHeaders = 0; +static int showSymbols = 0; +static int showRelocs = 0; +static int disassemble = 0; + +/********************************************************************** + * Private Constant Data + **********************************************************************/ + +static const struct option long_options[] = +{ + {"all", 0, NULL, 'a'}, + {"file-header", 0, NULL, 'h'}, + {"section-headers", 0, NULL, 'S'}, + {"symbols", 0, NULL, 's'}, + {"relocs", 0, NULL, 'r'}, + {"disassemble", 0, NULL, 'd'}, + {"help", 0, NULL, 'H'}, + {NULL, 0, NULL, 0} +}; + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +static void showUsage (const char *progname); +static void parseArgs (int argc, char **argv); +static void dumpProgramData (poffHandle_t poffHandle); + +/********************************************************************** + * Global Functions + **********************************************************************/ + +int main (int argc, char *argv[], char *envp[]) +{ + FILE *object; /* Object file pointer */ + poffHandle_t poffHandle; /* Handle for POFF object */ + char fileName[FNAME_SIZE+1]; /* Object file name */ + uint16_t errCode; /* See pedefs.h */ + + /* Parse the command line arguments */ + + parseArgs(argc, argv); + + /* Open source POFF file -- Use .o or command line extension, if supplied */ + + (void) extension (poffFileName, "o", fileName, 0); + if (!(object = fopen (fileName, "rb"))) + { + printf ("Error opening %s\n", fileName); + exit (1); + } /* end if */ + + /* Read the POFF file */ + + poffHandle = poffCreateHandle(); + if (poffHandle == NULL) + { + printf ("Could not get POFF handler\n"); + exit (1); + } + + errCode = poffReadFile(poffHandle, object); + if (errCode != eNOERROR) + { + printf ("Could not read POFF file\n"); + exit (1); + } + + /* Dump the File Header */ + + if (showFileHeader) + { + poffDumpFileHeader(poffHandle, stdout); + } + + /* Dump the Section Headers */ + + if (showSectionHeaders) + { + poffDumpSectionHeaders(poffHandle, stdout); + } + + /* Dump the symbol table */ + + if (showSymbols) + { + poffDumpSymbolTable(poffHandle, stdout); + } + + /* Dump the relocation table */ + + if (showRelocs) + { + poffDumpRelocTable(poffHandle, stdout); + } + + /* Dump the program data section -- Main Loop */ + + if (disassemble) + { + dumpProgramData(poffHandle); + } + + /* Close files and release objects */ + + poffDestroyHandle(poffHandle); + (void)fclose(object); + return 0; +} /* end main */ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +static void showUsage(const char *progname) +{ + fprintf(stderr, "Usage:\n"); + fprintf(stderr, " %s [options] \n", + progname); + fprintf(stderr, "options:\n"); + fprintf(stderr, " -a --all Equivalent to: -h -S -s -r -d\n"); + fprintf(stderr, " -h --file-header Display the POFF file header\n"); + fprintf(stderr, " -S --section-headers Display the sections' header\n"); + fprintf(stderr, " -s --symbols Display the symbol table\n"); + fprintf(stderr, " -r --relocs Display the relocations\n"); + fprintf(stderr, " -d --disassemble Display disassembled text\n"); + fprintf(stderr, " -H --help Display this information\n"); + exit(1); +} + +/***********************************************************************/ + +static void parseArgs(int argc, char **argv) +{ + int option_index; + int c; + + /* Check for existence of filename argument */ + + if (argc < 2) + { + fprintf(stderr, "ERROR: POFF filename required\n"); + showUsage(argv[0]); + } /* end if */ + + /* Parse the command line options */ + + do + { + c = getopt_long (argc, argv, "ahSsrdH", + long_options, &option_index); + if (c != -1) + { + switch (c) + { + case 'a' : + showFileHeader = 1; + showSectionHeaders = 1; + showSymbols = 1; + showRelocs = 1; + disassemble = 1; + break; + + case 'h' : + showFileHeader = 1; + break; + + case 'S' : + showSectionHeaders = 1; + break; + + case 's' : + showSymbols = 1; + break; + + case 'r' : + showRelocs = 1; + break; + + case 'd' : + disassemble = 1; + break; + + case 'H' : + showUsage(argv[0]); + break; + + default: + /* Shouldn't happen */ + + fprintf(stderr, "ERROR: Unrecognized option\n"); + showUsage(argv[0]); + } + } + } + while (c != -1); + + /* Get the name of the p-code file(s) from the last argument(s) */ + + if (optind != argc-1) + { + fprintf(stderr, "ERROR: POFF filename required as final argument\n"); + showUsage(argv[0]); + } + + /* Save the POFF file name */ + + poffFileName = argv[argc-1]; +} + +/***********************************************************************/ + +static void dumpProgramData(poffHandle_t poffHandle) +{ + poffLibLineNumber_t *lastln; /* Previous line number reference */ + poffLibLineNumber_t *ln; /* Current line number reference */ + poffLibDebugFuncInfo_t *dfi; /* Current line debug info */ + uint32_t pc; /* Program counter */ + int opSize; /* Size of the opcode */ + int inch; /* Input char */ + OPTYPE op; /* opcode */ + + /* Read the line number entries from the POFF file */ + + poffReadLineNumberTable(poffHandle); + + /* Read the debug function information from the POFF file */ + + poffReadDebugFuncInfoTable(poffHandle); + + /* Dump the program data section -- DumpProgramData Loop */ + + pc = 0; + lastln = NULL; + + while ((inch = poffGetProgByte(poffHandle)) != EOF) + { + /* Get opcode arguments (if any) */ + + op.op = inch; + opSize = 1; + + if (inch & o32) + { + uint32_t arg; + + /* Handle 32-bits in big endian byte stream */ + + arg = poffGetProgByte(poffHandle) << 24; + arg |= poffGetProgByte(poffHandle) << 16; + arg |= poffGetProgByte(poffHandle) << 8; + arg |= poffGetProgByte(poffHandle); + + op.arg = arg; + opSize += 4; + } + + /* Check for debug information associated with this line */ + + dfi = poffFindDebugFuncInfo(pc); + if (dfi) + { + int i; + if (dfi->retsize) + { + printf("\nFUNCTION ENTRY: return size=%ld nparms=%ld\n", + dfi->retsize, dfi->nparms); + } + else + { + printf("\nPROCEDURE ENTRY: nparms=%ld\n", dfi->nparms); + } + + for (i = 0; i < dfi->nparms; i++) + { + printf("Argument %2d: size=%ld\n", i, dfi->argsize[i]); + } + } + + /* Find the line number associated with this line */ + + ln = poffFindLineNumber(pc); + if ((ln) && (ln != lastln)) + { + /* Print the line number line */ + + printf("\n%s:%ld\n", ln->filename, ln->lineno); + + /* This will suppress reporting the same line number + * repeatedly. + */ + + lastln = ln; + } + + /* Print the address then the opcode on stdout */ + + fprintf(stdout, "%08lx ", pc); + insn_DisassemblePCode(stdout, &op); + + /* Bump the PC to the next address */ + + pc += opSize; + + } /* end while */ + + /* Release buffers associated with line number and debug information */ + + poffReleaseLineNumberTable(); + poffReleaseDebugFuncInfoTable(); + +} /* end dumpProgramData */ + +/***********************************************************************/ diff --git a/misc/pascal/insn32/popt/pcopt.c b/misc/pascal/insn32/popt/pcopt.c index ee5f4d924..2c4c1fa01 100644 --- a/misc/pascal/insn32/popt/pcopt.c +++ b/misc/pascal/insn32/popt/pcopt.c @@ -1,839 +1,840 @@ -/********************************************************************** - * pcopt.c - * Constant Expression Optimizations - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include - -#include "keywords.h" -#include "pdefs.h" -#include "pinsn32.h" - -#include "paslib.h" -#include "popt.h" -#include "polocal.h" -#include "pcopt.h" - -/**********************************************************************/ - -int unaryOptimize(void) -{ - register uint32 temp; - register int i; - int nchanges = 0; - - TRACE(stderr, "[unaryOptimize]"); - - /* At least two pcodes are need to perform unary optimizations */ - - i = 0; - while (i < nops-1) - { - /* Check for a constant value being pushed onto the stack */ - - if (GETOP(pptr[i]) == oPUSH) - { - switch (GETOP(pptr[i+1])) - { - /* Delete unary operators on constants */ - case oNEG : - PUTARG(pptr[i], -GETARG(pptr[i])); - deletePcode(i+1); - nchanges++; - break; - - case oABS : - if ((sint32)GETARG(pptr[i]) < 0) - PUTARG(pptr[i], -(sint32)GETARG(pptr[i])); - deletePcode(i+1); - nchanges++; - break; - - case oINC : - PUTARG(pptr[i], GETARG(pptr[i]) + 1); - deletePcode(i+1); - nchanges++; - break; - - case oDEC : - PUTARG(pptr[i], GETARG(pptr[i]) - 1); - deletePcode(i+1); - nchanges++; - break; - - case oNOT : - PUTARG(pptr[i], ~GETARG(pptr[i])); - PUTARG(pptr[i], ~(GETARG(pptr[i]))); - deletePcode(i+1); - nchanges++; - break; - - /* Simplify binary operations on constants */ - - case oADD : - if (GETARG(pptr[i]) == 0) - { - deletePcodePair(i, (i+1)); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i+1], oINC); - deletePcode(i); - nchanges++; - } /* end else if */ - else if (GETARG(pptr[i]) == ARGONES) - { - PUTOP(pptr[i+1], oDEC); - deletePcode(i); - nchanges++; - } /* end else if */ - else i++; - break; - - case oSUB : - if (GETARG(pptr[i]) == 0) - { - deletePcodePair(i, (i+1)); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i+1], oDEC); - deletePcode(i); - nchanges++; - } /* end else if */ - else if (GETARG(pptr[i]) == ARGONES) - { - PUTOP(pptr[i+1], oINC); - deletePcode(i); - nchanges++; - } /* end else if */ - else i++; - break; - - case oMUL : - case oDIV : - temp = 0; - switch (GETARG(pptr[i])) - { - case 1 : - deletePcodePair(i, (i+1)); - nchanges++; - break; - case 16384 : temp++; - case 8192 : temp++; - case 4096 : temp++; - case 2048 : temp++; - case 1024 : temp++; - case 512 : temp++; - case 256 : temp++; - case 128 : temp++; - case 64 : temp++; - case 32 : temp++; - case 16 : temp++; - case 8 : temp++; - case 4 : temp++; - case 2 : temp++; - PUTARG(pptr[i], temp); - if (GETOP(pptr[i+1]) == oMUL) - PUTOP(pptr[i+1], oSLL); - else - PUTOP(pptr[i+1], oSRA); - nchanges++; - i++; - break; - - default : - i++; - break; - } /* end switch */ - break; - - case oSLL : - case oSRL : - case oSRA : - case oOR : - if (GETARG(pptr[i]) == 0) - { - deletePcodePair(i, (i+1)); - nchanges++; - } /* end if */ - else i++; - break; - - case oAND : - if (GETARG(pptr[i]) == ARGONES) - { - deletePcodePair(i, (i+1)); - nchanges++; - } /* end if */ - else i++; - break; - - /* Delete comparisons of constants to zero */ - - case oEQUZ : - if (GETARG(pptr[i]) == 0) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcode(i+1); - nchanges++; - break; - - case oNEQZ : - if (GETARG(pptr[i]) != 0) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcode(i+1); - nchanges++; - break; - - case oLTZ : - if ((sint32)GETARG(pptr[i]) < 0) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcode(i+1); - nchanges++; - break; - - case oGTEZ : - if ((sint32)GETARG(pptr[i]) >= 0) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcode(i+1); - nchanges++; - break; - - case oGTZ : - if (GETARG(pptr[i]) > 0) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcode(i+1); - nchanges++; - break; - - case oLTEZ : - if (GETARG(pptr[i]) <= 0) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcode(i+1); - nchanges++; - break; - - /* Simplify comparisons with certain constants */ - - case oEQU : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+1],oEQUZ); - deletePcode(i); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i], oDEC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oEQUZ); - nchanges++; - } /* end else if */ - else if ((sint32)GETARG(pptr[i]) == -1) - { - PUTOP(pptr[i], oINC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oEQUZ); - nchanges++; - } /* end else if */ - else i++; - break; - - case oNEQ : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+1], oNEQZ); - deletePcode(i); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i], oDEC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oNEQZ); - nchanges++; - } /* end else if */ - else if ((sint32)GETARG(pptr[i]) == -1) - { - PUTOP(pptr[i], oINC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oNEQZ); - nchanges++; - } /* end else if */ - else i++; - break; - - case oLT : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+1], oLTZ); - deletePcode(i); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i], oDEC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oLTZ); - nchanges++; - } /* end else if */ - else if ((sint32)GETARG(pptr[i]) == -1) - { - PUTOP(pptr[i], oINC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oLTZ); - nchanges++; - } /* end else if */ - else i++; - break; - - case oGTE : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+1], oGTEZ); - deletePcode(i); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i], oDEC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oGTEZ); - nchanges++; - } /* end else if */ - else if ((sint32)GETARG(pptr[i]) == -1) - { - PUTOP(pptr[i], oINC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oGTEZ); - nchanges++; - } /* end else if */ - else i++; - break; - - case oGT : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+1], oGTZ); - deletePcode(i); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i], oDEC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oGTZ); - nchanges++; - } /* end else if */ - else if ((sint32)GETARG(pptr[i]) == -1) - { - PUTOP(pptr[i], oINC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oGTZ); - nchanges++; - } /* end else if */ - else i++; - break; - - case oLTE : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+1], oLTEZ); - deletePcode(i); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i], oDEC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oLTEZ); - nchanges++; - } /* end else if */ - else if ((sint32)GETARG(pptr[i]) == -1) - { - PUTOP(pptr[i], oINC); - PUTARG(pptr[i], 0); - PUTOP(pptr[i+1], oLTEZ); - nchanges++; - } /* end else if */ - else i++; - break; - - /* Simplify or delete condition branches on constants */ - - case oJEQUZ : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+1], oJMP); - deletePcode(i); - } /* end if */ - else - deletePcodePair(i, (i+1)); - nchanges++; - break; - - case oJNEQZ : - if (GETARG(pptr[i]) != 0) - { - PUTOP(pptr[i+1], oJMP); - deletePcode(i); - } /* end if */ - else - deletePcodePair(i, (i+1)); - nchanges++; - break; - - case oJLTZ : - if ((sint32)GETARG(pptr[i]) < 0) - { - PUTOP(pptr[i+1], oJMP); - deletePcode(i); - } /* end if */ - else - deletePcodePair(i, (i+1)); - nchanges++; - break; - - case oJGTEZ : - if ((sint32)GETARG(pptr[i]) >= 0) - { - PUTOP(pptr[i+1], oJMP); - deletePcode(i); - } /* end if */ - else - deletePcodePair(i, (i+1)); - nchanges++; - break; - - case oJGTZ : - if (GETARG(pptr[i]) > 0) - { - PUTOP(pptr[i+1], oJMP); - deletePcode(i); - } /* end if */ - else - deletePcodePair(i, (i+1)); - nchanges++; - break; - - case oJLTEZ : - if (GETARG(pptr[i]) <= 0) - { - PUTOP(pptr[i+1], oJMP); - deletePcode(i); - } /* end if */ - else - deletePcodePair(i, (i+1)); - nchanges++; - break; - - default : - i++; - break; - } /* end switch */ - } /* end if */ - - /* Delete multiple modifications of DSEG pointer */ - - else if (GETOP(pptr[i]) == oINDS) - { - if (GETOP(pptr[i+1]) == oINDS) - { - PUTARG(pptr[i], GETARG(pptr[i] + GETARG(pptr[i+1]))); - deletePcode(i+1); - } /* end if */ - else i++; - } /* end else if */ - else i++; - } /* end while */ - - return (nchanges); - -} /* end unaryOptimize */ - -/**********************************************************************/ - -int binaryOptimize(void) -{ - register int i; - int nchanges = 0; - - TRACE(stderr, "[binaryOptimize]"); - - /* At least two pcodes are needed to perform the following binary */ - /* operator optimizations */ - - i = 0; - while (i < nops-2) - { - if (GETOP(pptr[i]) == oPUSH) - { - if (GETOP(pptr[i+1]) == oPUSH) - { - switch (GETOP(pptr[i+2])) - { - case oADD : - PUTARG(pptr[i], GETARG(pptr[i]) + GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oSUB : - PUTARG(pptr[i], GETARG(pptr[i]) - GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oMUL : - PUTARG(pptr[i], GETARG(pptr[i]) * GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oDIV : - PUTARG(pptr[i], GETARG(pptr[i]) / (sint32)GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oMOD : - PUTARG(pptr[i], GETARG(pptr[i]) % GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oSLL : - PUTARG(pptr[i], GETARG(pptr[i]) << GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oSRL : - PUTARG(pptr[i], GETARG(pptr[i]) >> GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oSRA : - PUTARG(pptr[i], (sint32)GETARG(pptr[i]) >> GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oOR : - PUTARG(pptr[i], GETARG(pptr[i]) | GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oAND : - PUTARG(pptr[i], GETARG(pptr[i]) & GETARG(pptr[i+1])); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oEQU : - if (GETARG(pptr[i]) == GETARG(pptr[i+1])) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oNEQ : - if (GETARG(pptr[i]) != GETARG(pptr[i+1])) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oLT : - if ((sint32)GETARG(pptr[i]) < (sint32)GETARG(pptr[i+1])) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oGTE : - if ((sint32)GETARG(pptr[i]) >= (sint32)GETARG(pptr[i+1])) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oGT : - if ((sint32)GETARG(pptr[i]) > (sint32)GETARG(pptr[i+1])) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - case oLTE : - if ((sint32)GETARG(pptr[i]) <= (sint32)GETARG(pptr[i+1])) - PUTARG(pptr[i], -1); - else - PUTARG(pptr[i], 0); - deletePcodePair((i+1), (i+2)); - nchanges++; - break; - - default : - i++; - break; - } /* end switch */ - } /* end if */ - - /* A single (constant) pcode is sufficient to perform the */ - /* following binary operator optimizations */ - - else if ((GETOP(pptr[i+1]) == oLDSH) || (GETOP(pptr[i+1]) == oLDSB) || - (GETOP(pptr[i+1]) == oLAS) || (GETOP(pptr[i+1]) == oLAC)) - { - switch (GETOP(pptr[i+2])) - { - case oADD : - if (GETARG(pptr[i]) == 0) - { - deletePcodePair(i, (i+2)); - nchanges++; - } /* end if */ - else if (GETARG(pptr[i]) == 1) - { - PUTOP(pptr[i+2], oINC); - deletePcode(i); - nchanges++; - } /* end else if */ - else if (GETARG(pptr[i]) == ARGONES) - { - PUTOP(pptr[i+2], oDEC); - deletePcode(i); - nchanges++; - } /* end else if */ - else i++; - break; - - case oSUB : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i], oNEG); - deletePcode(i); - nchanges++; - } /* end if */ - else i++; - break; - - case oMUL : - { - sint32 stmp32 = 0; - switch (GETARG(pptr[i])) - { - case 1 : - deletePcodePair(i, (i+2)); - nchanges++; - break; - case 16384 : stmp32++; - case 8192 : stmp32++; - case 4096 : stmp32++; - case 2048 : stmp32++; - case 1024 : stmp32++; - case 512 : stmp32++; - case 256 : stmp32++; - case 128 : stmp32++; - case 64 : stmp32++; - case 32 : stmp32++; - case 16 : stmp32++; - case 8 : stmp32++; - case 4 : stmp32++; - case 2 : stmp32++; - PUTOP(pptr[i], GETOP(pptr[i+1])); - PUTARG(pptr[i], GETARG(pptr[i+1])); - PUTOP(pptr[i+1], oPUSH); - PUTARG(pptr[i+1], stmp32); - PUTOP(pptr[i+2], oSLL); - nchanges++; - i++; - break; - - default : - i++; - break; - } - } - break; - - case oOR : - if (GETARG(pptr[i]) == 0) - { - deletePcodePair(i, (i+2)); - nchanges++; - } /* end if */ - else i++; - break; - - case oAND : - if (GETARG(pptr[i]) == ARGONES) - { - deletePcodePair(i, (i+2)); - nchanges++; - } /* end if */ - else i++; - break; - - case oEQU : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+2], oEQUZ); - deletePcode(i); - nchanges++; - } /* end if */ - else i++; - break; - - case oNEQ : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+2], oNEQZ); - deletePcode(i); - nchanges++; - } /* end if */ - else i++; - break; - - case oLT : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+2], oGTEZ); - deletePcode(i); - nchanges++; - } /* end if */ - else i++; - break; - - case oGTE : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+2], oLTZ); - deletePcode(i); - nchanges++; - } /* end if */ - else i++; - break; - - case oGT : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+2], oLTEZ); - deletePcode(i); - nchanges++; - } /* end if */ - else i++; - break; - - case oLTE : - if (GETARG(pptr[i]) == 0) - { - PUTOP(pptr[i+2], oGTZ); - deletePcode(i); - nchanges++; - } /* end if */ - else i++; - break; - - default : - i++; - break; - - } /* end switch */ - } /* end else if */ - else i++; - } /* end if */ - - /* Misc improvements on binary operators */ - - else if (GETOP(pptr[i]) == oNEG) - { - /* Negation followed by add is subtraction */ - - if (GETOP(pptr[i+1]) == oADD) - { - PUTOP(pptr[i+1], oSUB); - deletePcode(i); - nchanges++; - } - - /* Negation followed by subtraction is addition */ - - else if (GETOP(pptr[i]) == oSUB) - { - PUTOP(pptr[i+1], oADD); - deletePcode(i); - nchanges++; - } - else i++; - } - else i++; - } /* end while */ - - return (nchanges); - -} /* end binaryOptimize */ - -/**********************************************************************/ +/********************************************************************** + * pcopt.c + * Constant Expression Optimizations + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include + +#include "keywords.h" +#include "pdefs.h" +#include "pinsn32.h" + +#include "paslib.h" +#include "popt.h" +#include "polocal.h" +#include "pcopt.h" + +/**********************************************************************/ + +int unaryOptimize(void) +{ + register uint32_t temp; + register int i; + int nchanges = 0; + + TRACE(stderr, "[unaryOptimize]"); + + /* At least two pcodes are need to perform unary optimizations */ + + i = 0; + while (i < nops-1) + { + /* Check for a constant value being pushed onto the stack */ + + if (GETOP(pptr[i]) == oPUSH) + { + switch (GETOP(pptr[i+1])) + { + /* Delete unary operators on constants */ + case oNEG : + PUTARG(pptr[i], -GETARG(pptr[i])); + deletePcode(i+1); + nchanges++; + break; + + case oABS : + if ((int32_t)GETARG(pptr[i]) < 0) + PUTARG(pptr[i], -(int32_t)GETARG(pptr[i])); + deletePcode(i+1); + nchanges++; + break; + + case oINC : + PUTARG(pptr[i], GETARG(pptr[i]) + 1); + deletePcode(i+1); + nchanges++; + break; + + case oDEC : + PUTARG(pptr[i], GETARG(pptr[i]) - 1); + deletePcode(i+1); + nchanges++; + break; + + case oNOT : + PUTARG(pptr[i], ~GETARG(pptr[i])); + PUTARG(pptr[i], ~(GETARG(pptr[i]))); + deletePcode(i+1); + nchanges++; + break; + + /* Simplify binary operations on constants */ + + case oADD : + if (GETARG(pptr[i]) == 0) + { + deletePcodePair(i, (i+1)); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i+1], oINC); + deletePcode(i); + nchanges++; + } /* end else if */ + else if (GETARG(pptr[i]) == ARGONES) + { + PUTOP(pptr[i+1], oDEC); + deletePcode(i); + nchanges++; + } /* end else if */ + else i++; + break; + + case oSUB : + if (GETARG(pptr[i]) == 0) + { + deletePcodePair(i, (i+1)); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i+1], oDEC); + deletePcode(i); + nchanges++; + } /* end else if */ + else if (GETARG(pptr[i]) == ARGONES) + { + PUTOP(pptr[i+1], oINC); + deletePcode(i); + nchanges++; + } /* end else if */ + else i++; + break; + + case oMUL : + case oDIV : + temp = 0; + switch (GETARG(pptr[i])) + { + case 1 : + deletePcodePair(i, (i+1)); + nchanges++; + break; + case 16384 : temp++; + case 8192 : temp++; + case 4096 : temp++; + case 2048 : temp++; + case 1024 : temp++; + case 512 : temp++; + case 256 : temp++; + case 128 : temp++; + case 64 : temp++; + case 32 : temp++; + case 16 : temp++; + case 8 : temp++; + case 4 : temp++; + case 2 : temp++; + PUTARG(pptr[i], temp); + if (GETOP(pptr[i+1]) == oMUL) + PUTOP(pptr[i+1], oSLL); + else + PUTOP(pptr[i+1], oSRA); + nchanges++; + i++; + break; + + default : + i++; + break; + } /* end switch */ + break; + + case oSLL : + case oSRL : + case oSRA : + case oOR : + if (GETARG(pptr[i]) == 0) + { + deletePcodePair(i, (i+1)); + nchanges++; + } /* end if */ + else i++; + break; + + case oAND : + if (GETARG(pptr[i]) == ARGONES) + { + deletePcodePair(i, (i+1)); + nchanges++; + } /* end if */ + else i++; + break; + + /* Delete comparisons of constants to zero */ + + case oEQUZ : + if (GETARG(pptr[i]) == 0) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcode(i+1); + nchanges++; + break; + + case oNEQZ : + if (GETARG(pptr[i]) != 0) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcode(i+1); + nchanges++; + break; + + case oLTZ : + if ((int32_t)GETARG(pptr[i]) < 0) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcode(i+1); + nchanges++; + break; + + case oGTEZ : + if ((int32_t)GETARG(pptr[i]) >= 0) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcode(i+1); + nchanges++; + break; + + case oGTZ : + if (GETARG(pptr[i]) > 0) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcode(i+1); + nchanges++; + break; + + case oLTEZ : + if (GETARG(pptr[i]) <= 0) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcode(i+1); + nchanges++; + break; + + /* Simplify comparisons with certain constants */ + + case oEQU : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+1],oEQUZ); + deletePcode(i); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i], oDEC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oEQUZ); + nchanges++; + } /* end else if */ + else if ((int32_t)GETARG(pptr[i]) == -1) + { + PUTOP(pptr[i], oINC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oEQUZ); + nchanges++; + } /* end else if */ + else i++; + break; + + case oNEQ : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+1], oNEQZ); + deletePcode(i); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i], oDEC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oNEQZ); + nchanges++; + } /* end else if */ + else if ((int32_t)GETARG(pptr[i]) == -1) + { + PUTOP(pptr[i], oINC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oNEQZ); + nchanges++; + } /* end else if */ + else i++; + break; + + case oLT : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+1], oLTZ); + deletePcode(i); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i], oDEC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oLTZ); + nchanges++; + } /* end else if */ + else if ((int32_t)GETARG(pptr[i]) == -1) + { + PUTOP(pptr[i], oINC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oLTZ); + nchanges++; + } /* end else if */ + else i++; + break; + + case oGTE : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+1], oGTEZ); + deletePcode(i); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i], oDEC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oGTEZ); + nchanges++; + } /* end else if */ + else if ((int32_t)GETARG(pptr[i]) == -1) + { + PUTOP(pptr[i], oINC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oGTEZ); + nchanges++; + } /* end else if */ + else i++; + break; + + case oGT : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+1], oGTZ); + deletePcode(i); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i], oDEC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oGTZ); + nchanges++; + } /* end else if */ + else if ((int32_t)GETARG(pptr[i]) == -1) + { + PUTOP(pptr[i], oINC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oGTZ); + nchanges++; + } /* end else if */ + else i++; + break; + + case oLTE : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+1], oLTEZ); + deletePcode(i); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i], oDEC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oLTEZ); + nchanges++; + } /* end else if */ + else if ((int32_t)GETARG(pptr[i]) == -1) + { + PUTOP(pptr[i], oINC); + PUTARG(pptr[i], 0); + PUTOP(pptr[i+1], oLTEZ); + nchanges++; + } /* end else if */ + else i++; + break; + + /* Simplify or delete condition branches on constants */ + + case oJEQUZ : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+1], oJMP); + deletePcode(i); + } /* end if */ + else + deletePcodePair(i, (i+1)); + nchanges++; + break; + + case oJNEQZ : + if (GETARG(pptr[i]) != 0) + { + PUTOP(pptr[i+1], oJMP); + deletePcode(i); + } /* end if */ + else + deletePcodePair(i, (i+1)); + nchanges++; + break; + + case oJLTZ : + if ((int32_t)GETARG(pptr[i]) < 0) + { + PUTOP(pptr[i+1], oJMP); + deletePcode(i); + } /* end if */ + else + deletePcodePair(i, (i+1)); + nchanges++; + break; + + case oJGTEZ : + if ((int32_t)GETARG(pptr[i]) >= 0) + { + PUTOP(pptr[i+1], oJMP); + deletePcode(i); + } /* end if */ + else + deletePcodePair(i, (i+1)); + nchanges++; + break; + + case oJGTZ : + if (GETARG(pptr[i]) > 0) + { + PUTOP(pptr[i+1], oJMP); + deletePcode(i); + } /* end if */ + else + deletePcodePair(i, (i+1)); + nchanges++; + break; + + case oJLTEZ : + if (GETARG(pptr[i]) <= 0) + { + PUTOP(pptr[i+1], oJMP); + deletePcode(i); + } /* end if */ + else + deletePcodePair(i, (i+1)); + nchanges++; + break; + + default : + i++; + break; + } /* end switch */ + } /* end if */ + + /* Delete multiple modifications of DSEG pointer */ + + else if (GETOP(pptr[i]) == oINDS) + { + if (GETOP(pptr[i+1]) == oINDS) + { + PUTARG(pptr[i], GETARG(pptr[i] + GETARG(pptr[i+1]))); + deletePcode(i+1); + } /* end if */ + else i++; + } /* end else if */ + else i++; + } /* end while */ + + return (nchanges); + +} /* end unaryOptimize */ + +/**********************************************************************/ + +int binaryOptimize(void) +{ + register int i; + int nchanges = 0; + + TRACE(stderr, "[binaryOptimize]"); + + /* At least two pcodes are needed to perform the following binary */ + /* operator optimizations */ + + i = 0; + while (i < nops-2) + { + if (GETOP(pptr[i]) == oPUSH) + { + if (GETOP(pptr[i+1]) == oPUSH) + { + switch (GETOP(pptr[i+2])) + { + case oADD : + PUTARG(pptr[i], GETARG(pptr[i]) + GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oSUB : + PUTARG(pptr[i], GETARG(pptr[i]) - GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oMUL : + PUTARG(pptr[i], GETARG(pptr[i]) * GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oDIV : + PUTARG(pptr[i], GETARG(pptr[i]) / (int32_t)GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oMOD : + PUTARG(pptr[i], GETARG(pptr[i]) % GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oSLL : + PUTARG(pptr[i], GETARG(pptr[i]) << GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oSRL : + PUTARG(pptr[i], GETARG(pptr[i]) >> GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oSRA : + PUTARG(pptr[i], (int32_t)GETARG(pptr[i]) >> GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oOR : + PUTARG(pptr[i], GETARG(pptr[i]) | GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oAND : + PUTARG(pptr[i], GETARG(pptr[i]) & GETARG(pptr[i+1])); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oEQU : + if (GETARG(pptr[i]) == GETARG(pptr[i+1])) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oNEQ : + if (GETARG(pptr[i]) != GETARG(pptr[i+1])) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oLT : + if ((int32_t)GETARG(pptr[i]) < (int32_t)GETARG(pptr[i+1])) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oGTE : + if ((int32_t)GETARG(pptr[i]) >= (int32_t)GETARG(pptr[i+1])) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oGT : + if ((int32_t)GETARG(pptr[i]) > (int32_t)GETARG(pptr[i+1])) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + case oLTE : + if ((int32_t)GETARG(pptr[i]) <= (int32_t)GETARG(pptr[i+1])) + PUTARG(pptr[i], -1); + else + PUTARG(pptr[i], 0); + deletePcodePair((i+1), (i+2)); + nchanges++; + break; + + default : + i++; + break; + } /* end switch */ + } /* end if */ + + /* A single (constant) pcode is sufficient to perform the */ + /* following binary operator optimizations */ + + else if ((GETOP(pptr[i+1]) == oLDSH) || (GETOP(pptr[i+1]) == oLDSB) || + (GETOP(pptr[i+1]) == oLAS) || (GETOP(pptr[i+1]) == oLAC)) + { + switch (GETOP(pptr[i+2])) + { + case oADD : + if (GETARG(pptr[i]) == 0) + { + deletePcodePair(i, (i+2)); + nchanges++; + } /* end if */ + else if (GETARG(pptr[i]) == 1) + { + PUTOP(pptr[i+2], oINC); + deletePcode(i); + nchanges++; + } /* end else if */ + else if (GETARG(pptr[i]) == ARGONES) + { + PUTOP(pptr[i+2], oDEC); + deletePcode(i); + nchanges++; + } /* end else if */ + else i++; + break; + + case oSUB : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i], oNEG); + deletePcode(i); + nchanges++; + } /* end if */ + else i++; + break; + + case oMUL : + { + int32_t stmp32 = 0; + switch (GETARG(pptr[i])) + { + case 1 : + deletePcodePair(i, (i+2)); + nchanges++; + break; + case 16384 : stmp32++; + case 8192 : stmp32++; + case 4096 : stmp32++; + case 2048 : stmp32++; + case 1024 : stmp32++; + case 512 : stmp32++; + case 256 : stmp32++; + case 128 : stmp32++; + case 64 : stmp32++; + case 32 : stmp32++; + case 16 : stmp32++; + case 8 : stmp32++; + case 4 : stmp32++; + case 2 : stmp32++; + PUTOP(pptr[i], GETOP(pptr[i+1])); + PUTARG(pptr[i], GETARG(pptr[i+1])); + PUTOP(pptr[i+1], oPUSH); + PUTARG(pptr[i+1], stmp32); + PUTOP(pptr[i+2], oSLL); + nchanges++; + i++; + break; + + default : + i++; + break; + } + } + break; + + case oOR : + if (GETARG(pptr[i]) == 0) + { + deletePcodePair(i, (i+2)); + nchanges++; + } /* end if */ + else i++; + break; + + case oAND : + if (GETARG(pptr[i]) == ARGONES) + { + deletePcodePair(i, (i+2)); + nchanges++; + } /* end if */ + else i++; + break; + + case oEQU : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+2], oEQUZ); + deletePcode(i); + nchanges++; + } /* end if */ + else i++; + break; + + case oNEQ : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+2], oNEQZ); + deletePcode(i); + nchanges++; + } /* end if */ + else i++; + break; + + case oLT : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+2], oGTEZ); + deletePcode(i); + nchanges++; + } /* end if */ + else i++; + break; + + case oGTE : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+2], oLTZ); + deletePcode(i); + nchanges++; + } /* end if */ + else i++; + break; + + case oGT : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+2], oLTEZ); + deletePcode(i); + nchanges++; + } /* end if */ + else i++; + break; + + case oLTE : + if (GETARG(pptr[i]) == 0) + { + PUTOP(pptr[i+2], oGTZ); + deletePcode(i); + nchanges++; + } /* end if */ + else i++; + break; + + default : + i++; + break; + + } /* end switch */ + } /* end else if */ + else i++; + } /* end if */ + + /* Misc improvements on binary operators */ + + else if (GETOP(pptr[i]) == oNEG) + { + /* Negation followed by add is subtraction */ + + if (GETOP(pptr[i+1]) == oADD) + { + PUTOP(pptr[i+1], oSUB); + deletePcode(i); + nchanges++; + } + + /* Negation followed by subtraction is addition */ + + else if (GETOP(pptr[i]) == oSUB) + { + PUTOP(pptr[i+1], oADD); + deletePcode(i); + nchanges++; + } + else i++; + } + else i++; + } /* end while */ + + return (nchanges); + +} /* end binaryOptimize */ + +/**********************************************************************/ diff --git a/misc/pascal/insn32/popt/pfopt.c b/misc/pascal/insn32/popt/pfopt.c index de07400bf..cf71fe005 100644 --- a/misc/pascal/insn32/popt/pfopt.c +++ b/misc/pascal/insn32/popt/pfopt.c @@ -2,7 +2,7 @@ * pfopt.c * Finalization of optimized image * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -38,6 +38,7 @@ * Included Files **********************************************************************/ +#include #include #include #include @@ -85,7 +86,7 @@ static void pass1(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) { OPTYPE op; - uint32 pc; + uint32_t pc; int opsize; int fileno = 0; @@ -106,22 +107,22 @@ static void pass1(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) { opsize = insn_GetOpCode(poffHandle, &op); if (GETOP(&op) == oLABEL) - { - poffAddToDefinedLabelTable(GETARG(&op), pc); - } + { + poffAddToDefinedLabelTable(GETARG(&op), pc); + } else if (GETOP(&op) == oINCLUDE) - { - fileno = GETARG(&op); - } + { + fileno = GETARG(&op); + } else if (GETOP(&op) == oLINE) - { - poffAddLineNumber(poffHandle, GETARG(&op), fileno, pc); - } + { + poffAddLineNumber(poffHandle, GETARG(&op), fileno, pc); + } else - { - insn_AddTmpOpCode(poffProgHandle, &op); - pc += opsize; - } + { + insn_AddTmpOpCode(poffProgHandle, &op); + pc += opsize; + } } while (GETOP(&op) != oEND); @@ -135,8 +136,8 @@ static void pass1(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) static void pass2(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) { poffSymHandle_t poffSymHandle; - sint32 symIndex; - sint32 nchanges = 0; + int32_t symIndex; + int32_t nchanges = 0; /* Get a container to temporarily hold any modifications that we * make to the symbol table. @@ -158,49 +159,49 @@ static void pass2(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) poffLibSymbol_t symbol; symIndex = poffGetSymbol(poffHandle, &symbol); if (symIndex >= 0) - { - if ((symbol.type == STT_PROC) || (symbol.type == STT_FUNC)) - { - /* It is a symbol associated with the program data section. - * Has is value been defined? - */ - - if ((symbol.flags & STF_UNDEFINED) != 0) - { - /* No... Add it to the list of undefined labels */ - - poffAddToUndefinedLabelTable(symbol.value, symIndex); - } - else - { - /* It is a defined symbol. In this case, we should have - * encountered its LABEL marker in the pass1 processing - * and the following look up should not fail. - */ - sint32 value = poffGetPcForDefinedLabel(symbol.value); - if (value < 0) - { - DEBUG(stdout, "Failed to find label L%04lx\n", symbol.value); - fatal(ePOFFCONFUSION); - } - else - { - /* Replace the lavel value with the section offset - * (pc) value. - */ - - symbol.value = value; - nchanges++; - } - } - } - - /* In either event, we will want to save the symbol in case - * we need to re-write the symbol table. - */ - - (void)poffAddTmpSymbol(poffHandle, poffSymHandle, &symbol); - } + { + if ((symbol.type == STT_PROC) || (symbol.type == STT_FUNC)) + { + /* It is a symbol associated with the program data section. + * Has is value been defined? + */ + + if ((symbol.flags & STF_UNDEFINED) != 0) + { + /* No... Add it to the list of undefined labels */ + + poffAddToUndefinedLabelTable(symbol.value, symIndex); + } + else + { + /* It is a defined symbol. In this case, we should have + * encountered its LABEL marker in the pass1 processing + * and the following look up should not fail. + */ + int32_t value = poffGetPcForDefinedLabel(symbol.value); + if (value < 0) + { + DEBUG(stdout, "Failed to find label L%04lx\n", symbol.value); + fatal(ePOFFCONFUSION); + } + else + { + /* Replace the lavel value with the section offset + * (pc) value. + */ + + symbol.value = value; + nchanges++; + } + } + } + + /* In either event, we will want to save the symbol in case + * we need to re-write the symbol table. + */ + + (void)poffAddTmpSymbol(poffHandle, poffSymHandle, &symbol); + } } while (symIndex >= 0); @@ -223,9 +224,9 @@ static void pass2(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) static void pass3(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) { - OPTYPE op; - uint32 pc; - uint32 opsize; + OPTYPE op; + uint32_t pc; + uint32_t opsize; /* Read each opcode, generate relocation information and * replace label references with program section offsets. @@ -248,133 +249,133 @@ static void pass3(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) { opsize = insn_GetOpCode(poffHandle, &op); switch (GETOP(&op)) - { - /* Load of an address in the rodata section */ - - case oLAC: - /* We are referencing something from the rodata section. - * No special action need be taken. - */ - break; - - /* Call to a procedure or function. */ - - case oPCAL: - { - /* Check if this is a defined label, i.e., a call to - * procedure or function in the same file. - */ - - sint32 value = poffGetPcForDefinedLabel(GETARG(&op)); - if (value >= 0) - { - /* Yes... replace the label reference with - * a text section offset. No relocation record - * is needed in this case. The only relocation - * may be performed is a subsequent program data - * section offset. - */ - - PUTARG(&op, value); - } - else - { - /* Check if this is a undefined label. This would - * occur for a call to a procedure or a function that - * is defined in some other unit file. - */ - - value = poffGetSymIndexForUndefinedLabel(GETARG(&op)); - if (value >= 0) - { - /* Use the value zero now */ - - PUTARG(&op, 0); - - /* And generate a symbol-based relocation */ - - (void)poffAddRelocation(poffHandle, RLT_PCAL, value, pc); - } - else - { - DEBUG(stdout, "Failed to find call label L%04x\n", - GETARG(&op)); - fatal(ePOFFCONFUSION); - } - } - } - break; - - /* Jumps to "nearby" addresses */ - - case oJMP: /* Unconditional */ - case oJEQUZ: /* Unary comparisons with zero */ - case oJNEQZ: - case oJLTZ: - case oJGTEZ: - case oJGTZ: - case oJLTEZ: - case oJEQU: /* Binary comparisons */ - case oJNEQ: - case oJLT: - case oJGTE: - case oJGT: - case oJLTE: - { - /* Check if this is a defined label. This must be the case - * because there can be no jumps into a unit file. - */ - - sint32 value = poffGetPcForDefinedLabel(GETARG(&op)); - if (value >= 0) - { - /* Yes... replace the label reference with - * a text section offset. No relocation record - * is needed in this case. The only relocation - * may be performed is a subsequent program data - * sectioin offset. - */ - - PUTARG(&op, value); - } - else - { - DEBUG(stdout, "Failed to find jump label L%04x\n", - GETARG(&op)); - fatal(ePOFFCONFUSION); - } - } - break; - - /* References to stack via level offset */ - - case oLAS: /* Load stack address */ - case oLASX: - case oLDS: /* Load value */ - case oLDSH: - case oLDSB: - case oLDSM: - case oSTS: /* Store value */ - case oSTSH: - case oSTSB: - case oSTSM: - case oLDSX: - case oLDSXH: /* Load value indexed */ - case oLDSXB: - case oLDSXM: - case oSTSX: /* Store value indexed */ - case oSTSXH: - case oSTSXB: - case oSTSXM: - { + { + /* Load of an address in the rodata section */ + + case oLAC: + /* We are referencing something from the rodata section. + * No special action need be taken. + */ + break; + + /* Call to a procedure or function. */ + + case oPCAL: + { + /* Check if this is a defined label, i.e., a call to + * procedure or function in the same file. + */ + + int32_t value = poffGetPcForDefinedLabel(GETARG(&op)); + if (value >= 0) + { + /* Yes... replace the label reference with + * a text section offset. No relocation record + * is needed in this case. The only relocation + * may be performed is a subsequent program data + * section offset. + */ + + PUTARG(&op, value); + } + else + { + /* Check if this is a undefined label. This would + * occur for a call to a procedure or a function that + * is defined in some other unit file. + */ + + value = poffGetSymIndexForUndefinedLabel(GETARG(&op)); + if (value >= 0) + { + /* Use the value zero now */ + + PUTARG(&op, 0); + + /* And generate a symbol-based relocation */ + + (void)poffAddRelocation(poffHandle, RLT_PCAL, value, pc); + } + else + { + DEBUG(stdout, "Failed to find call label L%04x\n", + GETARG(&op)); + fatal(ePOFFCONFUSION); + } + } + } + break; + + /* Jumps to "nearby" addresses */ + + case oJMP: /* Unconditional */ + case oJEQUZ: /* Unary comparisons with zero */ + case oJNEQZ: + case oJLTZ: + case oJGTEZ: + case oJGTZ: + case oJLTEZ: + case oJEQU: /* Binary comparisons */ + case oJNEQ: + case oJLT: + case oJGTE: + case oJGT: + case oJLTE: + { + /* Check if this is a defined label. This must be the case + * because there can be no jumps into a unit file. + */ + + int32_t value = poffGetPcForDefinedLabel(GETARG(&op)); + if (value >= 0) + { + /* Yes... replace the label reference with + * a text section offset. No relocation record + * is needed in this case. The only relocation + * may be performed is a subsequent program data + * sectioin offset. + */ + + PUTARG(&op, value); + } + else + { + DEBUG(stdout, "Failed to find jump label L%04x\n", + GETARG(&op)); + fatal(ePOFFCONFUSION); + } + } + break; + + /* References to stack via level offset */ + + case oLAS: /* Load stack address */ + case oLASX: + case oLDS: /* Load value */ + case oLDSH: + case oLDSB: + case oLDSM: + case oSTS: /* Store value */ + case oSTSH: + case oSTSB: + case oSTSM: + case oLDSX: + case oLDSXH: /* Load value indexed */ + case oLDSXB: + case oLDSXM: + case oSTSX: /* Store value indexed */ + case oSTSXH: + case oSTSXB: + case oSTSXM: + { #warning REVISIT - } - break; + } + break; - /* Otherwise, it is not an interesting opcode */ - default: - break; - } + /* Otherwise, it is not an interesting opcode */ + default: + break; + } /* Save the potentially modified opcode in the temporary * program data container. @@ -405,13 +406,13 @@ static void pass4(poffHandle_t poffHandle) while ((pDebugInfo = poffGetDebugFuncInfo(poffHandle)) != NULL) { if (!pDebugInfoHead) - { - pDebugInfoHead = pDebugInfo; - } + { + pDebugInfoHead = pDebugInfo; + } else - { - pDebugInfoTail->next = pDebugInfo; - } + { + pDebugInfoTail->next = pDebugInfo; + } pDebugInfoTail = pDebugInfo; } @@ -423,17 +424,17 @@ static void pass4(poffHandle_t poffHandle) * because there can be no jumps into a unit file. */ - sint32 value = poffGetPcForDefinedLabel(pDebugInfo->value); + int32_t value = poffGetPcForDefinedLabel(pDebugInfo->value); if (value >= 0) - { - /* Yes... replace the label reference with a text section offset. */ + { + /* Yes... replace the label reference with a text section offset. */ - pDebugInfo->value = value; - } + pDebugInfo->value = value; + } else - { - fatal(ePOFFCONFUSION); - } + { + fatal(ePOFFCONFUSION); + } } /* Then put all of the debug info back into the POFF object */ @@ -460,9 +461,9 @@ static void pass4(poffHandle_t poffHandle) static void pass5(poffHandle_t poffHandle) { - uint32 entryLabel; - sint32 entryOffset; - ubyte fileType; + uint32_t entryLabel; + int32_t entryOffset; + uint8_t fileType; /* What kind of a file did we just process. Was it a program file? * or was it a unit file? @@ -481,9 +482,9 @@ static void pass5(poffHandle_t poffHandle) entryOffset = poffGetPcForDefinedLabel(entryLabel); if (entryOffset < 0) - { - fatal(ePOFFCONFUSION); - } + { + fatal(ePOFFCONFUSION); + } /* Replace file header entry point with the program data * section offset diff --git a/misc/pascal/insn32/popt/plopt.c b/misc/pascal/insn32/popt/plopt.c index d58f1a554..b0a469533 100644 --- a/misc/pascal/insn32/popt/plopt.c +++ b/misc/pascal/insn32/popt/plopt.c @@ -1,214 +1,215 @@ -/********************************************************************** - * plopt.c - * Load/Store Optimizations - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include - -#include "keywords.h" -#include "pdefs.h" -#include "pinsn32.h" - -#include "popt.h" -#include "polocal.h" -#include "plopt.h" - -/**********************************************************************/ - -int LoadOptimize(void) -{ - uint32 val; - int nchanges = 0; - register int i; - - TRACE(stderr, "[LoadOptimize]"); - - /* At least two pcodes are need to perform Load optimizations */ - - i = 0; - while (i < nops-1) - { - switch (GETOP(pptr[i])) - { - /* Eliminate duplicate loads */ - - case oLDSH : - if ((GETOP(pptr[i+1]) == oLDSH) && - (GETARG(pptr[i+1]) == GETARG(pptr[i]))) - { - PUTOP(pptr[i+1], oDUP); - PUTARG(pptr[i+1], 0); - nchanges++; - i += 2; - } /* end if */ - else i++; - break; - - /* Convert loads indexed by a constant to unindexed loads */ - - case oPUSH : - /* Get the index value */ - - val = (sint32)GETARG(pptr[i]); - - /* If the following instruction is a load, add the constant - * index value to the address and switch the opcode to the - * unindexed form. - */ - - if (GETOP(pptr[i+1]) == oLDSXH) - { - PUTOP(pptr[i+1], oLDSH); - val += GETARG(pptr[i+1]); - PUTARG(pptr[i+1], val); - deletePcode (i); - nchanges++; - } /* end if */ - else if (GETOP(pptr[i+1]) == oLASX) - { - PUTOP(pptr[i+1], oLAS); - val += GETARG(pptr[i+1]); - PUTARG(pptr[i+1], val); - deletePcode (i); - nchanges++; - } /* end else if */ - else if (GETOP(pptr[i+1]) == oLDSXB) - { - PUTOP(pptr[i+1], oLDSB); - val += GETARG(pptr[i+1]); - PUTARG(pptr[i+1], val); - deletePcode (i); - nchanges++; - } /* end if */ - else if (GETOP(pptr[i+1]) == oLDSXM) - { - PUTOP(pptr[i+1], oLDSM); - val += GETARG(pptr[i+1]); - PUTARG(pptr[i+1], val); - deletePcode (i); - nchanges++; - } /* end if */ - else i++; - break; - - default : - i++; - break; - } /* end switch */ - } /* end while */ - return (nchanges); -} /* end LoadOptimize */ - -/**********************************************************************/ -int StoreOptimize (void) -{ - uint32 val; - int nchanges = 0; - register int i; - - TRACE(stderr, "[StoreOptimize]"); - - /* At least two pcodes are need to perform the following Store */ - /* optimizations */ - - i = 0; - while (i < nops-1) - { - switch (GETOP(pptr[i])) - { - /* Eliminate store followed by load */ - - case oSTSH : - if ((GETOP(pptr[i+1]) == oLDSH) && - (GETARG(pptr[i+1]) == GETARG(pptr[i]))) - { - PUTOP(pptr[i+1], oSTSH); - PUTOP(pptr[i], oDUP); - PUTARG(pptr[i], 0); - nchanges++; - i += 2; - } /* end if */ - else i++; - break; - - /* Convert stores indexed by a constant to unindexed stores */ - case oPUSH : - /* Get the index value */ - - val = (sint32)GETARG(pptr[i]); - - /* If the following instruction is a store, add the constant - * index value to the address and switch the opcode to the - * unindexed form. - */ - - if (i < nops-2) - { - if (GETOP(pptr[i+2]) == oSTSXH) - { - PUTOP(pptr[i+2], oSTSH); - val += GETARG(pptr[i+2]); - PUTARG(pptr[i+2], val); - deletePcode (i); - nchanges++; - } /* end if */ - else if (GETOP(pptr[i+2]) == oSTSXB) - { - PUTOP(pptr[i+2], oSTSB); - val += GETARG(pptr[i+2]); - PUTARG(pptr[i+2], val); - deletePcode (i); - nchanges++; - } /* end if */ - else i++; - } /* end if */ - else i++; - break; - - default : - i++; - break; - } /* end switch */ - } /* end while */ - - return (nchanges); - -} /* end StoreOptimize */ - -/**********************************************************************/ - +/********************************************************************** + * plopt.c + * Load/Store Optimizations + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include + +#include "keywords.h" +#include "pdefs.h" +#include "pinsn32.h" + +#include "popt.h" +#include "polocal.h" +#include "plopt.h" + +/**********************************************************************/ + +int LoadOptimize(void) +{ + uint32_t val; + int nchanges = 0; + register int i; + + TRACE(stderr, "[LoadOptimize]"); + + /* At least two pcodes are need to perform Load optimizations */ + + i = 0; + while (i < nops-1) + { + switch (GETOP(pptr[i])) + { + /* Eliminate duplicate loads */ + + case oLDSH : + if ((GETOP(pptr[i+1]) == oLDSH) && + (GETARG(pptr[i+1]) == GETARG(pptr[i]))) + { + PUTOP(pptr[i+1], oDUP); + PUTARG(pptr[i+1], 0); + nchanges++; + i += 2; + } /* end if */ + else i++; + break; + + /* Convert loads indexed by a constant to unindexed loads */ + + case oPUSH : + /* Get the index value */ + + val = (int32_t)GETARG(pptr[i]); + + /* If the following instruction is a load, add the constant + * index value to the address and switch the opcode to the + * unindexed form. + */ + + if (GETOP(pptr[i+1]) == oLDSXH) + { + PUTOP(pptr[i+1], oLDSH); + val += GETARG(pptr[i+1]); + PUTARG(pptr[i+1], val); + deletePcode (i); + nchanges++; + } /* end if */ + else if (GETOP(pptr[i+1]) == oLASX) + { + PUTOP(pptr[i+1], oLAS); + val += GETARG(pptr[i+1]); + PUTARG(pptr[i+1], val); + deletePcode (i); + nchanges++; + } /* end else if */ + else if (GETOP(pptr[i+1]) == oLDSXB) + { + PUTOP(pptr[i+1], oLDSB); + val += GETARG(pptr[i+1]); + PUTARG(pptr[i+1], val); + deletePcode (i); + nchanges++; + } /* end if */ + else if (GETOP(pptr[i+1]) == oLDSXM) + { + PUTOP(pptr[i+1], oLDSM); + val += GETARG(pptr[i+1]); + PUTARG(pptr[i+1], val); + deletePcode (i); + nchanges++; + } /* end if */ + else i++; + break; + + default : + i++; + break; + } /* end switch */ + } /* end while */ + return (nchanges); +} /* end LoadOptimize */ + +/**********************************************************************/ +int StoreOptimize (void) +{ + uint32_t val; + int nchanges = 0; + register int i; + + TRACE(stderr, "[StoreOptimize]"); + + /* At least two pcodes are need to perform the following Store */ + /* optimizations */ + + i = 0; + while (i < nops-1) + { + switch (GETOP(pptr[i])) + { + /* Eliminate store followed by load */ + + case oSTSH : + if ((GETOP(pptr[i+1]) == oLDSH) && + (GETARG(pptr[i+1]) == GETARG(pptr[i]))) + { + PUTOP(pptr[i+1], oSTSH); + PUTOP(pptr[i], oDUP); + PUTARG(pptr[i], 0); + nchanges++; + i += 2; + } /* end if */ + else i++; + break; + + /* Convert stores indexed by a constant to unindexed stores */ + case oPUSH : + /* Get the index value */ + + val = (int32_t)GETARG(pptr[i]); + + /* If the following instruction is a store, add the constant + * index value to the address and switch the opcode to the + * unindexed form. + */ + + if (i < nops-2) + { + if (GETOP(pptr[i+2]) == oSTSXH) + { + PUTOP(pptr[i+2], oSTSH); + val += GETARG(pptr[i+2]); + PUTARG(pptr[i+2], val); + deletePcode (i); + nchanges++; + } /* end if */ + else if (GETOP(pptr[i+2]) == oSTSXB) + { + PUTOP(pptr[i+2], oSTSB); + val += GETARG(pptr[i+2]); + PUTARG(pptr[i+2], val); + deletePcode (i); + nchanges++; + } /* end if */ + else i++; + } /* end if */ + else i++; + break; + + default : + i++; + break; + } /* end switch */ + } /* end while */ + + return (nchanges); + +} /* end StoreOptimize */ + +/**********************************************************************/ + diff --git a/misc/pascal/insn32/popt/psopt.c b/misc/pascal/insn32/popt/psopt.c index 6794115c8..16824106e 100644 --- a/misc/pascal/insn32/popt/psopt.c +++ b/misc/pascal/insn32/popt/psopt.c @@ -2,7 +2,7 @@ * psopt.c * String Stack Optimizaitons * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -46,6 +46,7 @@ * Included Files **********************************************************************/ +#include #include #include #include @@ -70,10 +71,10 @@ * Private Data **********************************************************************/ -static ubyte *pbuffer[NPBUFFERS]; -static int nbytes_in_pbuffer[NPBUFFERS]; -static int current_level = -1; -static int inch; +static uint8_t *pbuffer[NPBUFFERS]; +static int nbytes_in_pbuffer[NPBUFFERS]; +static int current_level = -1; +static int inch; /********************************************************************** * Private Function Prototypes @@ -97,7 +98,7 @@ static inline void putbuf(int c, poffProgHandle_t poffProgHandle) { /* No PUSHS encountered. Write byte directly to output */ - poffAddTmpProgByte(poffProgHandle, (ubyte)c); + poffAddTmpProgByte(poffProgHandle, (uint8_t)c); } else { @@ -106,7 +107,7 @@ static inline void putbuf(int c, poffProgHandle_t poffProgHandle) */ int idx = nbytes_in_pbuffer[dlvl]; - ubyte *dest = pbuffer[dlvl] + idx; + uint8_t *dest = pbuffer[dlvl] + idx; *dest = c; nbytes_in_pbuffer[dlvl] = idx + 1; } @@ -122,7 +123,7 @@ static inline void flushc(int c, poffProgHandle_t poffProgHandle) int dlvl = current_level - 1; int idx = nbytes_in_pbuffer[dlvl]; - ubyte *dest = pbuffer[dlvl] + idx; + uint8_t *dest = pbuffer[dlvl] + idx; *dest = c; nbytes_in_pbuffer[dlvl] = idx + 1; } @@ -132,7 +133,7 @@ static inline void flushc(int c, poffProgHandle_t poffProgHandle) * buffer */ - poffAddTmpProgByte(poffProgHandle, (ubyte)c); + poffAddTmpProgByte(poffProgHandle, (uint8_t)c); } } @@ -144,33 +145,33 @@ static inline void flushbuf(poffProgHandle_t poffProgHandle) if (nbytes_in_pbuffer[slvl] > 0) { if (current_level > 0) - { - /* Nested PUSHS encountered. Flush buffer into buffer associated - * with the previous nesting level. - */ - - int dlvl = slvl - 1; - ubyte *src = pbuffer[slvl]; - ubyte *dest = pbuffer[dlvl] + nbytes_in_pbuffer[dlvl]; - - memcpy(dest, src, nbytes_in_pbuffer[slvl]); - nbytes_in_pbuffer[dlvl] += nbytes_in_pbuffer[slvl]; - } + { + /* Nested PUSHS encountered. Flush buffer into buffer associated + * with the previous nesting level. + */ + + int dlvl = slvl - 1; + uint8_t *src = pbuffer[slvl]; + uint8_t *dest = pbuffer[dlvl] + nbytes_in_pbuffer[dlvl]; + + memcpy(dest, src, nbytes_in_pbuffer[slvl]); + nbytes_in_pbuffer[dlvl] += nbytes_in_pbuffer[slvl]; + } else - { - /* Only one PUSHS encountered. Flush directly to the output - * buffer - */ - - errCode = poffWriteTmpProgBytes(pbuffer[0], nbytes_in_pbuffer[0], - poffProgHandle); - - if (errCode != eNOERROR) - { - printf("Error writing to file: %d\n", errCode); - exit(1); - } - } + { + /* Only one PUSHS encountered. Flush directly to the output + * buffer + */ + + errCode = poffWriteTmpProgBytes(pbuffer[0], nbytes_in_pbuffer[0], + poffProgHandle); + + if (errCode != eNOERROR) + { + printf("Error writing to file: %d\n", errCode); + exit(1); + } + } } nbytes_in_pbuffer[slvl] = 0; } @@ -188,43 +189,43 @@ static void dopush(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) /* Search for a PUSHS opcode */ if (inch != oPUSHS) - { - /* Its not PUSHS, just echo to the output file/buffer */ + { + /* Its not PUSHS, just echo to the output file/buffer */ - putbuf(inch, poffProgHandle); + putbuf(inch, poffProgHandle); - /* Get the next byte from the input stream */ + /* Get the next byte from the input stream */ - opcode = inch; - inch = poffGetProgByte(poffHandle); + opcode = inch; + inch = poffGetProgByte(poffHandle); - /* Check for a 32-bit argument */ + /* Check for a 32-bit argument */ - if ((opcode & o32) != 0) - { - /* Echo the 32-bits of the argument */ + if ((opcode & o32) != 0) + { + /* Echo the 32-bits of the argument */ - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - } - } + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + } + } else - { - /* We have found PUSHS. No search for the next occurrence - * of either and instruction that increments the string - * stack or for the matching POPS - */ - - current_level++; - dopop(poffHandle, poffProgHandle); - current_level--; - } + { + /* We have found PUSHS. No search for the next occurrence + * of either and instruction that increments the string + * stack or for the matching POPS + */ + + current_level++; + dopop(poffHandle, poffProgHandle); + current_level--; + } } } @@ -244,97 +245,97 @@ static void dopop(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) /* Did we encounter another PUSHS? */ if (inch == oPUSHS) - { - /* Yes... recurse to handle it */ + { + /* Yes... recurse to handle it */ - current_level++; - dopop(poffHandle, poffProgHandle); - current_level--; - } + current_level++; + dopop(poffHandle, poffProgHandle); + current_level--; + } else if (inch == oPOPS) - { - /* Flush the buffered data without the PUSHS */ + { + /* Flush the buffered data without the PUSHS */ - flushbuf(poffProgHandle); + flushbuf(poffProgHandle); - /* And discard the matching POPS */ + /* And discard the matching POPS */ - inch = poffGetProgByte(poffHandle); - break; - } + inch = poffGetProgByte(poffHandle); + break; + } else if (inch == oLIB) - { - uint32 arg32; - unsigned int tmp; + { + uint32_t arg32; + unsigned int tmp; - /* Get the 32-bit argument from the big endian data stream */ + /* Get the 32-bit argument from the big endian data stream */ - tmp = poffGetProgByte(poffHandle); - arg32 = tmp << 24; - putbuf(tmp, poffProgHandle); + tmp = poffGetProgByte(poffHandle); + arg32 = tmp << 24; + putbuf(tmp, poffProgHandle); - tmp = poffGetProgByte(poffHandle); - arg32 |= tmp << 16; - putbuf(tmp, poffProgHandle); + tmp = poffGetProgByte(poffHandle); + arg32 |= tmp << 16; + putbuf(tmp, poffProgHandle); - tmp = poffGetProgByte(poffHandle); - arg32 |= tmp << 8; - putbuf(tmp, poffProgHandle); + tmp = poffGetProgByte(poffHandle); + arg32 |= tmp << 8; + putbuf(tmp, poffProgHandle); - tmp = poffGetProgByte(poffHandle); - arg32 |= tmp; - putbuf(tmp, poffProgHandle); + tmp = poffGetProgByte(poffHandle); + arg32 |= tmp; + putbuf(tmp, poffProgHandle); - inch = poffGetProgByte(poffHandle); + inch = poffGetProgByte(poffHandle); - /* Is it LIB MKSTK? MKSTKSTR? or MKSTKC? */ + /* Is it LIB MKSTK? MKSTKSTR? or MKSTKC? */ - if ((arg32 == lbMKSTK) || - (arg32 == lbMKSTKSTR) || - (arg32 == lbMKSTKC)) - { - /* Flush the buffered data with the PUSHS */ + if ((arg32 == lbMKSTK) || + (arg32 == lbMKSTKSTR) || + (arg32 == lbMKSTKC)) + { + /* Flush the buffered data with the PUSHS */ - flushc(oPUSHS, poffProgHandle); - flushbuf(poffProgHandle); + flushc(oPUSHS, poffProgHandle); + flushbuf(poffProgHandle); - /* And break out of the loop to search for - * the next PUSHS - */ + /* And break out of the loop to search for + * the next PUSHS + */ - break; - } - } + break; + } + } else - { - int opcode; + { + int opcode; - /* Something else. Put it in the buffer */ + /* Something else. Put it in the buffer */ - putbuf(inch, poffProgHandle); + putbuf(inch, poffProgHandle); - /* Get the next byte from the input stream */ + /* Get the next byte from the input stream */ - opcode = inch; - inch = poffGetProgByte(poffHandle); + opcode = inch; + inch = poffGetProgByte(poffHandle); - /* Check for a 32-bit argument */ + /* Check for a 32-bit argument */ - if (opcode & o32 != 0) - { - /* Buffer the remaining 24-bits of the argument */ + if (opcode & o32 != 0) + { + /* Buffer the remaining 24-bits of the argument */ - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - putbuf(inch, poffProgHandle); - inch = poffGetProgByte(poffHandle); - } - } + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + putbuf(inch, poffProgHandle); + inch = poffGetProgByte(poffHandle); + } + } } } @@ -343,7 +344,7 @@ static void dopop(poffHandle_t poffHandle, poffProgHandle_t poffProgHandle) **********************************************************************/ void stringStackOptimize(poffHandle_t poffHandle, - poffProgHandle_t poffProgHandle) + poffProgHandle_t poffProgHandle) { int i; @@ -351,12 +352,12 @@ void stringStackOptimize(poffHandle_t poffHandle, for (i = 0; i < NPBUFFERS; i++) { - pbuffer[i] = (ubyte*)malloc(PBUFFER_SIZE); + pbuffer[i] = (uint8_t*)malloc(PBUFFER_SIZE); if (pbuffer[i] == NULL) - { - printf("Failed to allocate pcode buffer\n"); - exit(1); - } + { + printf("Failed to allocate pcode buffer\n"); + exit(1); + } nbytes_in_pbuffer[i] = 0; } diff --git a/misc/pascal/insn32/regm/regm.c b/misc/pascal/insn32/regm/regm.c index eefc5e953..b037e87b2 100644 --- a/misc/pascal/insn32/regm/regm.c +++ b/misc/pascal/insn32/regm/regm.c @@ -1,341 +1,342 @@ -/********************************************************************** - * regm.c - * Convert 32-bit pcode defintions to a register model - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include -#include -#include - -#include "keywords.h" -#include "pdefs.h" -#include "pedefs.h" -#include "paslib.h" -#include "pofflib.h" -#include "perr.h" - -#include "regm.h" -#include "regm_tree.h" -#include "regm_pass1.h" -#include "regm_pass2.h" - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -static void regm_ShowUsage(const char *progname, int errcode); -static int regm_CheckPoffFile(poffHandle_t hPoff); -static poffHandle_t regm_ReadPoffFile(const char *filename); -static void regm_Pass3(poffHandle_t hPoff); -static void regm_Pass4(poffHandle_t hPoff); -static void regm_Pass5(poffHandle_t hPoff); -static void regm_WritePoffFile(poffHandle_t hPoff, - const char *filename); - -/********************************************************************** - * Public Variables - **********************************************************************/ - -int vRegmDebug = 0; - -/********************************************************************** - * Private Variables - **********************************************************************/ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/***********************************************************************/ - -static void regm_ShowUsage(const char *progname, int errcode) -{ - fprintf(stderr, "USAGE:\n"); - fprintf(stderr, " %s -h\n", progname); - fprintf(stderr, " %s [-d] \n", progname); - fprintf(stderr, "WHERE:\n"); - fprintf(stderr, " -d: Enables debug output\n"); - fprintf(stderr, " -h: Shows this message\n"); - exit(errcode); -} - -/***********************************************************************/ - -static poffHandle_t regm_ReadPoffFile(const char *filename) -{ - poffHandle_t hPoff; - char objname [FNAME_SIZE+1]; - FILE *objFile; - int errcode; - - TRACE(stderr, "[regm_ReadPoffFile]"); - - /* Open the optimized POFF object file -- Use the .o extension */ - - (void)extension(filename, "o", objname, 1); - if (!(objFile = fopen(objname, "rb"))) - { - printf("Error Opening %s\n", objname); - exit(1); - } - - /* Get a handle to a POFF input object */ - - hPoff = poffCreateHandle(); - if (!hPoff) - { - printf("Could not get POFF handle\n"); - exit(1); - } - - /* Read the POFF file into memory */ - - errcode = poffReadFile(hPoff, objFile); - if (errcode != 0) - { - printf("Could not read POFF file, errcode=0x%02x\n", errcode); - exit(1); - } - - /* Close the input file */ - - fclose(objFile); - return hPoff; -} - -/***********************************************************************/ - -static int regm_CheckPoffFile(poffHandle_t hPoff) -{ - ubyte fileArch = poffGetArchitecture(hPoff); - if (fileArch != FHA_PCODE_INSN32) - { - fprintf(stderr, "ERROR: File is not 32-bit pcode (%d)\n", - fileArch); - return -1; - } - return 0; -} - -/***********************************************************************/ -/* Pass3: Perform local optimization */ - -static void regm_Pass3(poffHandle_t hPoff) -{ - TRACE(stderr, "[regm_Pass3]"); -} - -/***********************************************************************/ -/* Pass 4: Fixup register usage, force to use a fixed number of registers - * (arguments, static registers, volatile registers, special registers), - * and add logic to handle large immediate values. - */ - -static void regm_Pass4(poffHandle_t hPoff) -{ - TRACE(stderr, "[regm_Pass4]"); -} - -/***********************************************************************/ -/* Pass 5: Fixup BL and B offsets, section headers, relocation entries, - * symbol values - */ - -static void regm_Pass5(poffHandle_t hPoff) -{ - TRACE(stderr, "[regm_Pass5]"); -} - -/***********************************************************************/ - -static void regm_WritePoffFile(poffHandle_t hPoff, const char *filename) -{ -#if 0 - char rexname [FNAME_SIZE+1]; - FILE *rexFile; - - TRACE(stderr, "[regm_WritePoffFile]"); - - /* Open optimized p-code file -- Use .o extension */ - - (void)extension(filename, ".rex", rexname, 1); - if (!(rexFile = fopen(rexname, "wb"))) - { - printf("Error Opening %s\n", rexname); - exit(1); - } - - /* Then write the new POFF file */ - - poffWritePoffFile(hPoff, rexFile); - - /* Destroy the POFF object */ - - poffDestroyHandle(hPoff); - - /* Close the files used on regm_WritePoffFile */ - - (void)fclose(rexFile); -#endif -} - -/********************************************************************** - * Public Functions - **********************************************************************/ - -/***********************************************************************/ - -int main(int argc, char *argv[], char *envp[]) -{ - const char *outfilename; - poffHandle_t hPoff; - TRACE(stderr, "[main]"); - int option; - - /* Process command line argruments */ - - while ((option = getopt(argc, argv, "dh")) > 0) - { - switch (option) - { - case 'd' : - vRegmDebug++; - break; - case 'h' : - regm_ShowUsage(argv[0], 0); - default: - fprintf(stderr, "Unrecognized option\n"); - regm_ShowUsage(argv[0], -1); - } - } - - /* Check for existence of filename argument */ - - if (optind != argc - 1) - { - fprintf(stderr, "Filename required at end of command line.\n"); - regm_ShowUsage(argv[0], -1); - } - - /* Read the POFF file into memory */ - - outfilename = argv[optind]; - hPoff = regm_ReadPoffFile(outfilename); - - /* Verify that it is the kind of file that we can handle */ - - if (regm_CheckPoffFile(hPoff) != 0) - { - fprintf(stderr, "File is not the correct type\n"); - regm_ShowUsage(argv[0], -1); - } - - /* Read the debug info into a more usable structure. And release - * the debug info in the POFF object (we will be replacing it later) - */ - - poffReadDebugFuncInfoTable(hPoff); - poffDiscardDebugFuncInfo(hPoff); - - /* Pass 1: Break the POFF program data into sections and buffer in - * a tree structure. - */ - - regm_InitTree(); - regm_Pass1(hPoff); - regm_DumpTree(); - - /* We can eliminate the buffered pcode data because we have - * a copy in the tree and we will be replacing it before we - * save the file. - */ - - poffReleaseProgData(hPoff); - - /* Pass 2: Convert the buffered pcode to the basic register model - * with an indefinite number of registers (arguments, general, and - * special registers) and with 32-bit immediate size. - */ - - regm_Pass2(hPoff); - - /* Pass3: Perform local optimization */ - - regm_Pass3(hPoff); - - /* Pass 4: Fixup register usage, force to use a fixed number of registers - * (arguments, static registers, volatile registers, special registers), - * and add logic to handle large immediate values. - */ - - regm_Pass4(hPoff); - - /* Pass 5: Fixup BL and B offsets, section headers, relocation entries, - * symbol values - */ - - regm_Pass5(hPoff); - - /* Replace the debug info in the POFF object with the debug info - * we have modified. We no longer need the buffered debug info after - * this point. - */ - - poffReplaceDebugFuncInfo(hPoff); - poffReleaseDebugFuncInfoTable(); - - /* Write the REGM POFF file */ - - poffSetArchitecture(hPoff, FHA_REGM_INSN32); - regm_WritePoffFile(hPoff, outfilename); - return 0; -} - -/***********************************************************************/ - -void regm_ProgSeek(poffHandle_t hPoff, uint32 dwOffset) -{ - insn_ResetOpCodeRead(hPoff); - if (poffProgSeek(hPoff, dwOffset) < 0) - { - fatal(eSEEKFAIL); - } -} - -/***********************************************************************/ - +/********************************************************************** + * regm.c + * Convert 32-bit pcode defintions to a register model + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include +#include +#include + +#include "keywords.h" +#include "pdefs.h" +#include "pedefs.h" +#include "paslib.h" +#include "pofflib.h" +#include "perr.h" + +#include "regm.h" +#include "regm_tree.h" +#include "regm_pass1.h" +#include "regm_pass2.h" + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +static void regm_ShowUsage(const char *progname, int errcode); +static int regm_CheckPoffFile(poffHandle_t hPoff); +static poffHandle_t regm_ReadPoffFile(const char *filename); +static void regm_Pass3(poffHandle_t hPoff); +static void regm_Pass4(poffHandle_t hPoff); +static void regm_Pass5(poffHandle_t hPoff); +static void regm_WritePoffFile(poffHandle_t hPoff, + const char *filename); + +/********************************************************************** + * Public Variables + **********************************************************************/ + +int vRegmDebug = 0; + +/********************************************************************** + * Private Variables + **********************************************************************/ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/***********************************************************************/ + +static void regm_ShowUsage(const char *progname, int errcode) +{ + fprintf(stderr, "USAGE:\n"); + fprintf(stderr, " %s -h\n", progname); + fprintf(stderr, " %s [-d] \n", progname); + fprintf(stderr, "WHERE:\n"); + fprintf(stderr, " -d: Enables debug output\n"); + fprintf(stderr, " -h: Shows this message\n"); + exit(errcode); +} + +/***********************************************************************/ + +static poffHandle_t regm_ReadPoffFile(const char *filename) +{ + poffHandle_t hPoff; + char objname [FNAME_SIZE+1]; + FILE *objFile; + int errcode; + + TRACE(stderr, "[regm_ReadPoffFile]"); + + /* Open the optimized POFF object file -- Use the .o extension */ + + (void)extension(filename, "o", objname, 1); + if (!(objFile = fopen(objname, "rb"))) + { + printf("Error Opening %s\n", objname); + exit(1); + } + + /* Get a handle to a POFF input object */ + + hPoff = poffCreateHandle(); + if (!hPoff) + { + printf("Could not get POFF handle\n"); + exit(1); + } + + /* Read the POFF file into memory */ + + errcode = poffReadFile(hPoff, objFile); + if (errcode != 0) + { + printf("Could not read POFF file, errcode=0x%02x\n", errcode); + exit(1); + } + + /* Close the input file */ + + fclose(objFile); + return hPoff; +} + +/***********************************************************************/ + +static int regm_CheckPoffFile(poffHandle_t hPoff) +{ + uint8_t fileArch = poffGetArchitecture(hPoff); + if (fileArch != FHA_PCODE_INSN32) + { + fprintf(stderr, "ERROR: File is not 32-bit pcode (%d)\n", + fileArch); + return -1; + } + return 0; +} + +/***********************************************************************/ +/* Pass3: Perform local optimization */ + +static void regm_Pass3(poffHandle_t hPoff) +{ + TRACE(stderr, "[regm_Pass3]"); +} + +/***********************************************************************/ +/* Pass 4: Fixup register usage, force to use a fixed number of registers + * (arguments, static registers, volatile registers, special registers), + * and add logic to handle large immediate values. + */ + +static void regm_Pass4(poffHandle_t hPoff) +{ + TRACE(stderr, "[regm_Pass4]"); +} + +/***********************************************************************/ +/* Pass 5: Fixup BL and B offsets, section headers, relocation entries, + * symbol values + */ + +static void regm_Pass5(poffHandle_t hPoff) +{ + TRACE(stderr, "[regm_Pass5]"); +} + +/***********************************************************************/ + +static void regm_WritePoffFile(poffHandle_t hPoff, const char *filename) +{ +#if 0 + char rexname [FNAME_SIZE+1]; + FILE *rexFile; + + TRACE(stderr, "[regm_WritePoffFile]"); + + /* Open optimized p-code file -- Use .o extension */ + + (void)extension(filename, ".rex", rexname, 1); + if (!(rexFile = fopen(rexname, "wb"))) + { + printf("Error Opening %s\n", rexname); + exit(1); + } + + /* Then write the new POFF file */ + + poffWritePoffFile(hPoff, rexFile); + + /* Destroy the POFF object */ + + poffDestroyHandle(hPoff); + + /* Close the files used on regm_WritePoffFile */ + + (void)fclose(rexFile); +#endif +} + +/********************************************************************** + * Public Functions + **********************************************************************/ + +/***********************************************************************/ + +int main(int argc, char *argv[], char *envp[]) +{ + const char *outfilename; + poffHandle_t hPoff; + TRACE(stderr, "[main]"); + int option; + + /* Process command line argruments */ + + while ((option = getopt(argc, argv, "dh")) > 0) + { + switch (option) + { + case 'd' : + vRegmDebug++; + break; + case 'h' : + regm_ShowUsage(argv[0], 0); + default: + fprintf(stderr, "Unrecognized option\n"); + regm_ShowUsage(argv[0], -1); + } + } + + /* Check for existence of filename argument */ + + if (optind != argc - 1) + { + fprintf(stderr, "Filename required at end of command line.\n"); + regm_ShowUsage(argv[0], -1); + } + + /* Read the POFF file into memory */ + + outfilename = argv[optind]; + hPoff = regm_ReadPoffFile(outfilename); + + /* Verify that it is the kind of file that we can handle */ + + if (regm_CheckPoffFile(hPoff) != 0) + { + fprintf(stderr, "File is not the correct type\n"); + regm_ShowUsage(argv[0], -1); + } + + /* Read the debug info into a more usable structure. And release + * the debug info in the POFF object (we will be replacing it later) + */ + + poffReadDebugFuncInfoTable(hPoff); + poffDiscardDebugFuncInfo(hPoff); + + /* Pass 1: Break the POFF program data into sections and buffer in + * a tree structure. + */ + + regm_InitTree(); + regm_Pass1(hPoff); + regm_DumpTree(); + + /* We can eliminate the buffered pcode data because we have + * a copy in the tree and we will be replacing it before we + * save the file. + */ + + poffReleaseProgData(hPoff); + + /* Pass 2: Convert the buffered pcode to the basic register model + * with an indefinite number of registers (arguments, general, and + * special registers) and with 32-bit immediate size. + */ + + regm_Pass2(hPoff); + + /* Pass3: Perform local optimization */ + + regm_Pass3(hPoff); + + /* Pass 4: Fixup register usage, force to use a fixed number of registers + * (arguments, static registers, volatile registers, special registers), + * and add logic to handle large immediate values. + */ + + regm_Pass4(hPoff); + + /* Pass 5: Fixup BL and B offsets, section headers, relocation entries, + * symbol values + */ + + regm_Pass5(hPoff); + + /* Replace the debug info in the POFF object with the debug info + * we have modified. We no longer need the buffered debug info after + * this point. + */ + + poffReplaceDebugFuncInfo(hPoff); + poffReleaseDebugFuncInfoTable(); + + /* Write the REGM POFF file */ + + poffSetArchitecture(hPoff, FHA_REGM_INSN32); + regm_WritePoffFile(hPoff, outfilename); + return 0; +} + +/***********************************************************************/ + +void regm_ProgSeek(poffHandle_t hPoff, uint32_t dwOffset) +{ + insn_ResetOpCodeRead(hPoff); + if (poffProgSeek(hPoff, dwOffset) < 0) + { + fatal(eSEEKFAIL); + } +} + +/***********************************************************************/ + diff --git a/misc/pascal/insn32/regm/regm.h b/misc/pascal/insn32/regm/regm.h index e90134516..4ab5999b1 100644 --- a/misc/pascal/insn32/regm/regm.h +++ b/misc/pascal/insn32/regm/regm.h @@ -1,65 +1,67 @@ -/*************************************************************************** - * regm.h - * External Declarations associated with regm.c - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ***************************************************************************/ - -#ifndef __REGM_H -#define __REGM_H - -/*************************************************************************** - * Included Files - ***************************************************************************/ - -/*************************************************************************** - * Definitions - ***************************************************************************/ - -#define dbg(format, arg...) \ - if (vRegmDebug) printf("%s: " format, __FUNCTION__, ##arg) - -#define DEBUG_FILE stdout - -/*************************************************************************** - * Global Variables - ***************************************************************************/ - -extern int vRegmDebug; - -/*************************************************************************** - * Global Function Prototypes - ***************************************************************************/ - -extern void regm_ProgSeek(poffHandle_t handle, uint32 dwOffset); - -#endif /* __REGM_H */ +/*************************************************************************** + * regm.h + * External Declarations associated with regm.c + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ***************************************************************************/ + +#ifndef __REGM_H +#define __REGM_H + +/*************************************************************************** + * Included Files + ***************************************************************************/ + +#include + +/*************************************************************************** + * Definitions + ***************************************************************************/ + +#define dbg(format, arg...) \ + if (vRegmDebug) printf("%s: " format, __FUNCTION__, ##arg) + +#define DEBUG_FILE stdout + +/*************************************************************************** + * Global Variables + ***************************************************************************/ + +extern int vRegmDebug; + +/*************************************************************************** + * Global Function Prototypes + ***************************************************************************/ + +extern void regm_ProgSeek(poffHandle_t handle, uint32_t dwOffset); + +#endif /* __REGM_H */ diff --git a/misc/pascal/insn32/regm/regm_pass1.c b/misc/pascal/insn32/regm/regm_pass1.c index 0ed1386d3..c3f5b30ef 100644 --- a/misc/pascal/insn32/regm/regm_pass1.c +++ b/misc/pascal/insn32/regm/regm_pass1.c @@ -1,279 +1,281 @@ -/********************************************************************** - * regm_pass1.c - * Break the pcode data into sections - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include -#include -#include - -#include "keywords.h" -#include "podefs.h" -#include "pedefs.h" -#include "paslib.h" -#include "pofflib.h" -#include "pinsn.h" -#include "pinsn32.h" -#include "perr.h" - -#include "regm.h" -#include "regm_tree.h" -#include "regm_pass1.h" - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -static void regm_Pass1Child(poffHandle_t hPoff, - struct procdata_s *pParent, - uint32 dwStartOffset, - uint32 dwEndOffset); -static void regm_Pass1Peer(poffHandle_t hPoff, - struct procdata_s *pPeer, - uint32 dwStartOffset, - uint32 dwEndOffset); -static struct procdata_s *regm_Pass1Node(poffHandle_t hPoff, - uint32 dwStartOffset, - uint32 pdwEndOffset, - ubyte chTerminator); -static uint32 regm_CheckSection1(poffHandle_t hPoff, uint32 dwOffset); -static void regm_Pass1Family(poffHandle_t hPoff, - struct procdata_s *pNode, - uint32 dwEndOffset); -/********************************************************************** - * Global Variables - **********************************************************************/ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/***********************************************************************/ - -static void regm_Pass1Child(poffHandle_t hPoff, struct procdata_s *pParent, - uint32 dwStartOffset, uint32 dwEndOffset) - -{ - struct procdata_s *pNode; - - TRACE(stderr, "[regm_Pass1Child]"); - - /* Read the proc/func body */ - - pNode = regm_Pass1Node(hPoff, dwStartOffset, dwEndOffset, oRET); - - /* Put the func/proc body section into the tree */ - - regm_AddProgChild(pParent, pNode); - - /* Handle nested and child proc/func blocks */ - - regm_Pass1Family(hPoff, pNode, dwEndOffset); -} - -/***********************************************************************/ - -static void regm_Pass1Peer(poffHandle_t hPoff, struct procdata_s *pPeer, - uint32 dwStartOffset, uint32 dwEndOffset) - -{ - struct procdata_s *pNode; - - TRACE(stderr, "[regm_Pass1Peer]"); - - /* Read the proc/func body */ - - pNode = regm_Pass1Node(hPoff, dwStartOffset, dwEndOffset, oRET); - - /* Put the func/proc body section into the tree */ - - regm_AddProgPeer(pPeer, pNode); - - /* Handle nested and child proc/func blocks */ - - regm_Pass1Family(hPoff, pNode, dwEndOffset); -} - -/***********************************************************************/ - -static struct procdata_s *regm_Pass1Node(poffHandle_t hPoff, - uint32 dwStartOffset, - uint32 pdwEndOffset, - ubyte chTerminator) - -{ - struct procdata_s *pNode; - uint32 dwActualEndOffset; - - TRACE(stderr, "[regm_Pass1Node]"); - - /* Create a container for the proc/func body, and read the data */ - - pNode = regm_CreateProgSection(); - - /* Check if there is a jump at the beginning of the segment */ - - pNode->section[0].dwOffset = dwStartOffset; - pNode->section[1].dwOffset = regm_CheckSection1(hPoff, dwStartOffset); - - /* Read all of the p-codes associated with the node */ - - dwActualEndOffset = regm_ReadNodePCodes(pNode, hPoff, - pNode->section[1].dwOffset, - pdwEndOffset, chTerminator); - - /* Now calculate the size of each part of the program section */ - - pNode->section[1].dwSize = dwActualEndOffset - pNode->section[1].dwOffset; - - if (pNode->section[0].dwOffset == pNode->section[1].dwOffset) - pNode->section[0].dwSize = 0; - else - pNode->section[0].dwSize = 5; - - /* Associate debug info with the program section. */ - - pNode->pFuncInfo = poffFindDebugFuncInfo(pNode->section[0].dwOffset); - if (!pNode->pFuncInfo) - { - /* This debug information should always be present at this - * point. We will need it. - */ - - fatal(ePOFFCONFUSION); - } - - return pNode; -} - -/***********************************************************************/ - -static uint32 regm_CheckSection1 (poffHandle_t hPoff, uint32 dwOffset) -{ - OPTYPE op; - - /* Seek to the beginning of the section. */ - - regm_ProgSeek(hPoff, dwOffset); - - /* Read the opcode at that position. */ - - (void)insn_GetOpCode(hPoff, &op); - - /* Is it a oJMP instruction? This happens when there are nested - * functions. The entry point into the parent function is a jump - * around the nested functions. - */ - - if (GETOP(&op) == oJMP) - { - /* Yes, then the block really begins at the target of the jump */ - - return GETARG(&op); - } - else - { - /* No, then the block really begins right here */ - - return dwOffset; - } -} - -/***********************************************************************/ - -static void regm_Pass1Family(poffHandle_t hPoff, struct procdata_s *pNode, - uint32 dwEndOffset) -{ - uint32 dwSectionEnd; - - /* Process any nested functions */ - - if (pNode->section[0].dwOffset != pNode->section[1].dwOffset) - { - dwSectionEnd = pNode->section[0].dwOffset + pNode->section[0].dwSize; - regm_Pass1Child(hPoff, pNode, dwSectionEnd, pNode->section[1].dwOffset); - } - - /* Process any peer functions */ - - dwSectionEnd = pNode->section[1].dwOffset + pNode->section[1].dwSize; - if (dwSectionEnd < dwEndOffset) - { - regm_Pass1Peer(hPoff, pNode, dwSectionEnd, dwEndOffset); - } -} - -/********************************************************************** - * Global Functions - **********************************************************************/ - -/***********************************************************************/ - -void regm_Pass1(poffHandle_t hPoff) -{ - struct procdata_s *pNode; - uint32 dwEntryPoint; - - TRACE(stderr, "[regm_Pass1]"); - - /* Get the program entry point from the poff header */ - - dwEntryPoint = poffGetEntryPoint(hPoff); - - /* Read the main program body */ - - pNode = regm_Pass1Node(hPoff, dwEntryPoint, 0xffffffff, oEND); - - /* Put the main program section into the tree (at the root) */ - - regm_SetProgRoot(pNode); - - /* Then process any nested functions */ - - if (dwEntryPoint != 0) - { - regm_Pass1Child(hPoff, pNode, 0, dwEntryPoint); - } -} - -/***********************************************************************/ - +/********************************************************************** + * regm_pass1.c + * Break the pcode data into sections + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include +#include +#include + +#include "keywords.h" +#include "podefs.h" +#include "pedefs.h" +#include "paslib.h" +#include "pofflib.h" +#include "pinsn.h" +#include "pinsn32.h" +#include "perr.h" + +#include "regm.h" +#include "regm_tree.h" +#include "regm_pass1.h" + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +static void regm_Pass1Child(poffHandle_t hPoff, + struct procdata_s *pParent, + uint32_t dwStartOffset, + uint32_t dwEndOffset); +static void regm_Pass1Peer(poffHandle_t hPoff, + struct procdata_s *pPeer, + uint32_t dwStartOffset, + uint32_t dwEndOffset); +static struct procdata_s *regm_Pass1Node(poffHandle_t hPoff, + uint32_t dwStartOffset, + uint32_t pdwEndOffset, + uint8_t chTerminator); +static uint32_t regm_CheckSection1(poffHandle_t hPoff, uint32_t dwOffset); +static void regm_Pass1Family(poffHandle_t hPoff, + struct procdata_s *pNode, + uint32_t dwEndOffset); + +/********************************************************************** + * Global Variables + **********************************************************************/ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/***********************************************************************/ + +static void regm_Pass1Child(poffHandle_t hPoff, struct procdata_s *pParent, + uint32_t dwStartOffset, uint32_t dwEndOffset) + +{ + struct procdata_s *pNode; + + TRACE(stderr, "[regm_Pass1Child]"); + + /* Read the proc/func body */ + + pNode = regm_Pass1Node(hPoff, dwStartOffset, dwEndOffset, oRET); + + /* Put the func/proc body section into the tree */ + + regm_AddProgChild(pParent, pNode); + + /* Handle nested and child proc/func blocks */ + + regm_Pass1Family(hPoff, pNode, dwEndOffset); +} + +/***********************************************************************/ + +static void regm_Pass1Peer(poffHandle_t hPoff, struct procdata_s *pPeer, + uint32_t dwStartOffset, uint32_t dwEndOffset) + +{ + struct procdata_s *pNode; + + TRACE(stderr, "[regm_Pass1Peer]"); + + /* Read the proc/func body */ + + pNode = regm_Pass1Node(hPoff, dwStartOffset, dwEndOffset, oRET); + + /* Put the func/proc body section into the tree */ + + regm_AddProgPeer(pPeer, pNode); + + /* Handle nested and child proc/func blocks */ + + regm_Pass1Family(hPoff, pNode, dwEndOffset); +} + +/***********************************************************************/ + +static struct procdata_s *regm_Pass1Node(poffHandle_t hPoff, + uint32_t dwStartOffset, + uint32_t pdwEndOffset, + uint8_t chTerminator) + +{ + struct procdata_s *pNode; + uint32_t dwActualEndOffset; + + TRACE(stderr, "[regm_Pass1Node]"); + + /* Create a container for the proc/func body, and read the data */ + + pNode = regm_CreateProgSection(); + + /* Check if there is a jump at the beginning of the segment */ + + pNode->section[0].dwOffset = dwStartOffset; + pNode->section[1].dwOffset = regm_CheckSection1(hPoff, dwStartOffset); + + /* Read all of the p-codes associated with the node */ + + dwActualEndOffset = regm_ReadNodePCodes(pNode, hPoff, + pNode->section[1].dwOffset, + pdwEndOffset, chTerminator); + + /* Now calculate the size of each part of the program section */ + + pNode->section[1].dwSize = dwActualEndOffset - pNode->section[1].dwOffset; + + if (pNode->section[0].dwOffset == pNode->section[1].dwOffset) + pNode->section[0].dwSize = 0; + else + pNode->section[0].dwSize = 5; + + /* Associate debug info with the program section. */ + + pNode->pFuncInfo = poffFindDebugFuncInfo(pNode->section[0].dwOffset); + if (!pNode->pFuncInfo) + { + /* This debug information should always be present at this + * point. We will need it. + */ + + fatal(ePOFFCONFUSION); + } + + return pNode; +} + +/***********************************************************************/ + +static uint32_t regm_CheckSection1 (poffHandle_t hPoff, uint32_t dwOffset) +{ + OPTYPE op; + + /* Seek to the beginning of the section. */ + + regm_ProgSeek(hPoff, dwOffset); + + /* Read the opcode at that position. */ + + (void)insn_GetOpCode(hPoff, &op); + + /* Is it a oJMP instruction? This happens when there are nested + * functions. The entry point into the parent function is a jump + * around the nested functions. + */ + + if (GETOP(&op) == oJMP) + { + /* Yes, then the block really begins at the target of the jump */ + + return GETARG(&op); + } + else + { + /* No, then the block really begins right here */ + + return dwOffset; + } +} + +/***********************************************************************/ + +static void regm_Pass1Family(poffHandle_t hPoff, struct procdata_s *pNode, + uint32_t dwEndOffset) +{ + uint32_t dwSectionEnd; + + /* Process any nested functions */ + + if (pNode->section[0].dwOffset != pNode->section[1].dwOffset) + { + dwSectionEnd = pNode->section[0].dwOffset + pNode->section[0].dwSize; + regm_Pass1Child(hPoff, pNode, dwSectionEnd, pNode->section[1].dwOffset); + } + + /* Process any peer functions */ + + dwSectionEnd = pNode->section[1].dwOffset + pNode->section[1].dwSize; + if (dwSectionEnd < dwEndOffset) + { + regm_Pass1Peer(hPoff, pNode, dwSectionEnd, dwEndOffset); + } +} + +/********************************************************************** + * Global Functions + **********************************************************************/ + +/***********************************************************************/ + +void regm_Pass1(poffHandle_t hPoff) +{ + struct procdata_s *pNode; + uint32_t dwEntryPoint; + + TRACE(stderr, "[regm_Pass1]"); + + /* Get the program entry point from the poff header */ + + dwEntryPoint = poffGetEntryPoint(hPoff); + + /* Read the main program body */ + + pNode = regm_Pass1Node(hPoff, dwEntryPoint, 0xffffffff, oEND); + + /* Put the main program section into the tree (at the root) */ + + regm_SetProgRoot(pNode); + + /* Then process any nested functions */ + + if (dwEntryPoint != 0) + { + regm_Pass1Child(hPoff, pNode, 0, dwEntryPoint); + } +} + +/***********************************************************************/ + diff --git a/misc/pascal/insn32/regm/regm_pass2.c b/misc/pascal/insn32/regm/regm_pass2.c index 03ef8dcd6..86380984d 100644 --- a/misc/pascal/insn32/regm/regm_pass2.c +++ b/misc/pascal/insn32/regm/regm_pass2.c @@ -1,1525 +1,1526 @@ -/********************************************************************** - * regm_pass2.c - * Convert the buffered pcode to the basic register model with an - * indefinite number of registers (arguments, general, and special - * registers) and with 32-bit immediate size. - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - *********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include -#include -#include - -#include "keywords.h" -#include "pdefs.h" -#include "pxdefs.h" -#include "pfdefs.h" -#include "pedefs.h" -#include "pofflib.h" -#include "perr.h" - -#include "pinsn32.h" -#include "builtins.h" - -#include "regm.h" -#include "regm_tree.h" -#include "regm_registers2.h" -#include "regm_pass2.h" - -/************************************a********************************* - * Definitions - **********************************************************************/ - -/********************************************************************** - * Private Types - **********************************************************************/ - -struct regm_opmap_s; - -typedef void (*regm_mapper_t)(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, struct procdata_s *pNode); - -struct regm_opmap_s -{ - ubyte chOpCode; - sbyte chImmediate; - sbyte chSpecial; - regm_mapper_t pMapper; -}; - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -static void regm_NoOperation(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_UnaryOperation(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_BinaryOperation(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_CompareVsZero(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_BinaryComparison(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_LoadImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_LoadMultiple(uint32 dwRDest, uint32 dwRSrc); -static void regm_LoadMultipleImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_StoreMultiple(uint32 dwRDest, uint32 dwRSrc); -static void regm_StoreImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_StoreMultipleImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_Duplicate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_PushImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_PopSpecial(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_SetDataCount(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_PushSpecial(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_Return(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_LoadOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_LoadMultipleOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_StoreOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_StoreMultipleOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_LoadIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, struct procdata_s *pNode); -static void regm_LoadMultipleIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_StoreIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, struct procdata_s *pNode); -static void regm_StoreMultipleIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_ConditionalBranchVsZero(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_ConditionalBranchBinary(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_UnconditionalBranch(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_IncrementSpecial(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_LoadAddress(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, struct procdata_s *pNode); -static void regm_LoadAddressIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_SetupOutArgs(uint32 nParms, const uint32 *pwArgSize); -static void regm_MapInRet(uint32 wRetSize); -static void regm_PCal(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_SysIo(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_LibCall(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_Float(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); -static void regm_IllegalPCode(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode); - -static void regm_GenerateRegm(struct procdata_s *pNode, void *pvArg); -static int regm_Pass2Node(struct procdata_s *pNode, void *pvArg); - -/********************************************************************** - * Public Variables - **********************************************************************/ - -/* On the initialize passes, the register number will simply be the offset - * from the top of the stack. The following variable keeps trck of the - * stack offset. - */ - -uint32 g_dwStackOffset; -uint32 g_dwRegisterCount = 0; -int g_bRegisterCountValid = 0; - -/********************************************************************** - * Private Variables - **********************************************************************/ - -static const struct regm_opmap_s vrgOpMap1[64] = - { - /* 0x00: oNOP */ {0, 0, 0, regm_NoOperation}, - /* 0x01: oNEG */ {rRSBI, 0, 0, regm_UnaryOperation}, - /* 0x02: oABS */ {rRSB, 0, 0, regm_UnaryOperation}, - /* 0x03: oINC */ {rADDI, 1, 0, regm_UnaryOperation}, - /* 0x04: oDEC */ {rSUBI, 1, 0, regm_UnaryOperation}, - /* 0x05: oNOT */ {rMVN, 0, 0, regm_UnaryOperation}, - /* 0x06: oADD */ {rADD, 0, 0, regm_BinaryOperation}, - /* 0x07: oSUB */ {rSUB, 0, 0, regm_BinaryOperation}, - /* 0x08: oMUL */ {rMUL, 0, 0, regm_BinaryOperation}, - /* 0x09: oDIV */ {rDIV, 0, 0, regm_BinaryOperation}, - /* 0x0a: oMOD */ {rMOD, 0, 0, regm_BinaryOperation}, - /* 0x0b: oSLL */ {rSLL, 0, 0, regm_BinaryOperation}, - /* 0x0c: oSRL */ {rSRL, 0, 0, regm_BinaryOperation}, - /* 0x0d: oSRA */ {rSRA, 0, 0, regm_BinaryOperation}, - /* 0x0e: oOR */ {rOR, 0, 0, regm_BinaryOperation}, - /* 0x0f: oAND */ {rAND, 0, 0, regm_BinaryOperation}, - - /* 0x10: oEQUZ */ {rBEQ, 0, 0, regm_CompareVsZero}, - /* 0x11: oNEQZ */ {rBNE, 0, 0, regm_CompareVsZero}, - /* 0x12: oLTZ */ {rBLT, 0, 0, regm_CompareVsZero}, - /* 0x13: oGTEZ */ {rBGTE, 0, 0, regm_CompareVsZero}, - /* 0x14: oGTZ */ {rBGT, 0, 0, regm_CompareVsZero}, - /* 0x15: oLTEZ */ {rBLTE, 0, 0, regm_CompareVsZero}, - /* 0x16: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x17: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x18: oEQU */ {rBEQ, 0, 0, regm_BinaryComparison}, - /* 0x19: oNEQ */ {rBNE, 0, 0, regm_BinaryComparison}, - /* 0x1a: oLT */ {rBLT, 0, 0, regm_BinaryComparison}, - /* 0x1b: oGTE */ {rBGTE, 0, 0, regm_BinaryComparison}, - /* 0x1c: oGT */ {rBGT, 0, 0, regm_BinaryComparison}, - /* 0x1d: oLTE */ {rBLTE, 0, 0, regm_BinaryComparison}, - /* 0x1e: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x1f: oBIT */ {rBEQ, 0, 0, regm_BinaryComparison}, - - /* 0x20: oLDI */ {rLD, 2, SPB, regm_LoadImmediate}, - /* 0x21: oLDIH */ {rLDH, 1, SPB, regm_LoadImmediate}, - /* 0x22: oLDIB */ {rLDB, 0, SPB, regm_LoadImmediate}, - /* 0x23: oLDIM */ {0, 0, SPB, regm_LoadMultipleImmediate}, - /* 0x24: oSTI */ {rST, 2, SPB, regm_StoreImmediate}, - /* 0x25: oSTIH */ {rSTH, 1, SPB, regm_StoreImmediate}, - /* 0x26: oSTIB */ {rSTB, 0, SPB, regm_StoreImmediate}, - /* 0x27: oSTIM */ {0, 0, SPB, regm_StoreMultipleImmediate}, - /* 0x28: oDUP */ {0, 0, 0, regm_Duplicate}, - /* 0x17: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x2a: oPUSHS */ {0, 0, CSP, regm_PushSpecial}, - /* 0x2b: oPOPS */ {0, 0, CSP, regm_PopSpecial}, - /* 0x2c: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x2d: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x2e: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x2f: oRET */ {0, 0, 0, regm_Return}, - - /* 0x30: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x31: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x32: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x33: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x34: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x35: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x36: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x37: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x38: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x39: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x3a: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x3b: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x3c: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x3d: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x3e: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x3f: oEND */ {0, 0, 0, regm_Return} - }; - -static const struct regm_opmap_s vrgOpMap2[64] = - { - /* 0x80: oLD */ {rLD, 2, SPB, regm_LoadOffset}, - /* 0x81: oLDH */ {rLDH, 1, SPB, regm_LoadOffset}, - /* 0x82: oLDB */ {rLDB, 0, SPB, regm_LoadOffset}, - /* 0x83: oLDM */ {0, 0, SPB, regm_LoadMultipleOffset}, - /* 0x84: oST */ {rST, 2, SPB, regm_StoreOffset}, - /* 0x85: oSTH */ {rSTH, 1, SPB, regm_StoreOffset}, - /* 0x86: oSTB */ {rSTB, 0, SPB, regm_StoreOffset}, - /* 0x87: oSTM */ {0, 0, SPB, regm_StoreMultipleOffset}, - /* 0x88: oLDX */ {rLD, 2, SPB, regm_LoadIndexed}, - /* 0x89: oLDXH */ {rLDH, 1, SPB, regm_LoadIndexed}, - /* 0x8a: oLDXB */ {rLDB, 0, SPB, regm_LoadIndexed}, - /* 0x8b: oLDXM */ {0, 0, SPB, regm_LoadMultipleIndexed}, - /* 0x8c: oSTX */ {rST, 2, SPB, regm_StoreIndexed}, - /* 0x8d: oSTXH */ {rSTH, 1, SPB, regm_StoreIndexed}, - /* 0x8e: oSTXB */ {rSTB, 0, SPB, regm_StoreIndexed}, - /* 0x8f: oSTXM */ {0, 0, SPB, regm_StoreMultipleIndexed}, - - /* 0x90: oJEQUZ */ {rBEQ, 0, 0, regm_ConditionalBranchVsZero}, - /* 0x91: oJNEQZ */ {rBNE, 0, 0, regm_ConditionalBranchVsZero}, - /* 0x92: oJLTZ */ {rBLT, 0, 0, regm_ConditionalBranchVsZero}, - /* 0x93: oJGTEZ */ {rBGTE, 0, 0, regm_ConditionalBranchVsZero}, - /* 0x94: oJGTZ */ {rBGT, 0, 0, regm_ConditionalBranchVsZero}, - /* 0x95: oJLTEZ */ {rBLTE, 0, 0, regm_ConditionalBranchVsZero}, - /* 0x96: oJMP */ {rB, 0, 0, regm_UnconditionalBranch}, - /* 0x97: oPUSH */ {0, 0, 0, regm_PushImmediate}, - /* 0x98: oJEQU */ {rBEQ, 0, 0, regm_ConditionalBranchBinary}, - /* 0x99: oJNEQ */ {rBNE, 0, 0, regm_ConditionalBranchBinary}, - /* 0x9a: oJLT */ {rBLT, 0, 0, regm_ConditionalBranchBinary}, - /* 0x9b: oJGTE */ {rBGTE, 0, 0, regm_ConditionalBranchBinary}, - /* 0x9c: oJGT */ {rBGT, 0, 0, regm_ConditionalBranchBinary}, - /* 0x9d: oJLTE */ {rBLTE, 0, 0, regm_ConditionalBranchBinary}, - /* 0x9e: */ {0, 0, 0, regm_IllegalPCode}, - /* 0x9f: oINDS */ {0, 0, SP, regm_IncrementSpecial}, - - /* 0xa0: oLDS */ {rLD, 2, LSP, regm_LoadOffset}, - /* 0xa1: oLDSH */ {rLDH, 1, LSP, regm_LoadOffset}, - /* 0xa2: oLDSB */ {rLDB, 0, LSP, regm_LoadOffset}, - /* 0xa3: oLDSM */ {0, 0, LSP, regm_LoadMultipleOffset}, - /* 0xa4: oSTS */ {rST, 2, LSP, regm_StoreOffset}, - /* 0xa5: oSTSH */ {rSTH, 1, LSP, regm_StoreOffset}, - /* 0xa6: oSTSB */ {rSTB, 0, LSP, regm_StoreOffset}, - /* 0xa7: oSTSM */ {0, 0, LSP, regm_StoreMultipleOffset}, - /* 0xa8: oLDSX */ {rLD, 2, LSP, regm_LoadIndexed}, - /* 0xa9: oLDSXH */ {rLDH, 1, LSP, regm_LoadIndexed}, - /* 0xaa: oLDSXB */ {rLDB, 0, LSP, regm_LoadIndexed}, - /* 0xab: oLDSXM */ {0, 0, LSP, regm_LoadMultipleIndexed}, - /* 0xac: oSTSX */ {rST, 2, LSP, regm_StoreIndexed}, - /* 0xad: oSTSXH */ {rSTH, 1, LSP, regm_StoreIndexed}, - /* 0xae: oSTSXB */ {rSTB, 0, LSP, regm_StoreIndexed}, - /* 0xaf: oSTSXM */ {0, 0, LSP, regm_StoreMultipleIndexed}, - - /* 0xb0: oLA */ {0, 0, SPB, regm_LoadAddress}, - /* 0xb1: oLAS */ {0, 0, LSP, regm_LoadAddress}, - /* 0xb2: oLAC */ {0, 0, CSB, regm_LoadAddress}, - /* 0xb3: */ {0, 0, 0, regm_IllegalPCode}, - /* 0xb4: oLAX */ {0, 0, SPB, regm_LoadAddressIndexed}, - /* 0xb5: oLASX */ {0, 0, LSP, regm_LoadAddressIndexed}, - /* 0xb6: oSLSP */ {0, 0, LSP, regm_PopSpecial}, - /* 0xb7: oSDC */ {0, 0, DC, regm_SetDataCount}, - /* 0xb8: */ {0, 0, 0, regm_IllegalPCode}, - /* 0xb9: oPCAL */ {0, 0, 0, regm_PCal}, - /* 0xba: oSYSIO */ {0, 0, 0, regm_SysIo}, - /* 0xbb: oLIB */ {0, 0, 0, regm_LibCall}, - /* 0xbc: oFLOAT */ {0, 0, 0, regm_Float}, - /* 0xbd: oLABEL */ {0, 0, 0, regm_NoOperation}, - /* 0xbe: oINCLUDE*/ {0, 0, 0, regm_NoOperation}, - /* 0xbf: oLINE */ {0, 0, 0, regm_NoOperation} - }; - -static const struct regm_builtin_s g_rgSysIoBuiltIns[MAX_XOP] = -{ - /* 0x00 */ ILLEGAL_BUILTIN_INIT, xEOF_INIT, - /* 0x02 */ xEOLN_INIT, xRESET_INIT, - /* 0x04 */ xREWRITE_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x06 */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x08 */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x0a */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x0c */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x0e */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x10 */ xREADLN_INIT, xREAD_PAGE_INIT, - /* 0x12 */ xREAD_BINARY_INIT, xREAD_INT_INIT, - /* 0x14 */ xREAD_CHAR_INIT, xREAD_STRING_INIT, - /* 0x16 */ xREAD_REAL_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x18 */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x1a */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x1c */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x1e */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x20 */ xWRITELN_INIT, xWRITE_PAGE_INIT, - /* 0x22 */ xWRITE_BINARY_INIT, xWRITE_INT_INIT, - /* 0x24 */ xWRITE_CHAR_INIT, xWRITE_STRING_INIT, - /* 0x25 */ xWRITE_REAL_INIT -}; - -static const struct regm_builtin_s g_rgLibCallBuiltIns[MAX_LBOP] = -{ - /* 0x00 */ lbGETENV_INIT, lbSTR2STR_INIT, - /* 0x02 */ lbCSTR2STR_INIT, lbSTR2RSTR_INIT, - /* 0x04 */ lbCSTR2RSTR_INIT, lbVAL_INIT, - /* 0x06 */ lbMKSTK_INIT, lbMKSTKSTR_INIT, - /* 0x08 */ lbMKSTKC_INIT, lbSTRCAT_INIT, - /* 0x0a */ lbSTRCATC_INIT, lbSTRCMP_INIT -}; - -static const struct regm_builtin_s g_rgRrFopBuiltIns[MAX_FOP] = -{ - /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, - /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, - /* 0x04 */ fpADD_RR_INIT, fpSUB_RR_INIT, - /* 0x06 */ fpMUL_RR_INIT, fpDIV_RR_INIT, - /* 0x00 */ fpMOD_RR_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x0a */ fpEQU_RR_INIT, fpNEQ_RR_INIT, - /* 0x0c */ fpLT_RR_INIT, fpGTE_RR_INIT, - /* 0x0e */ fpGT_RR_INIT, fpLTE_RR_INIT, - /* 0x10 */ fpNEG_R_INIT, fpABS_R_INIT, - /* 0x12 */ fpSQR_R_INIT, fpSQRT_R_INIT, - /* 0x14 */ fpSIN_R_INIT, fpCOS_R_INIT, - /* 0x16 */ fpATAN_R_INIT, fpLN_R_INIT, - /* 0x18 */ fpEXP_R_INIT -}; - -static const struct regm_builtin_s g_rgRiFopBuiltIns[MAX_FOP] = -{ - /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, - /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, - /* 0x04 */ fpADD_RI_INIT, fpSUB_RI_INIT, - /* 0x06 */ fpMUL_RI_INIT, fpDIV_RI_INIT, - /* 0x00 */ fpMOD_RI_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x0a */ fpEQU_RI_INIT, fpNEQ_RI_INIT, - /* 0x0c */ fpLT_RI_INIT, fpGTE_RI_INIT, - /* 0x0e */ fpGT_RI_INIT, fpLTE_RI_INIT, - /* 0x10 */ fpNEG_I_INIT, fpABS_I_INIT, - /* 0x12 */ fpSQR_I_INIT, fpSQRT_I_INIT, - /* 0x14 */ fpSIN_I_INIT, fpCOS_I_INIT, - /* 0x16 */ fpATAN_I_INIT, fpLN_I_INIT, - /* 0x18 */ fpEXP_I_INIT -}; - -static const struct regm_builtin_s g_rgIrFopBuiltIns[MAX_FOP] = -{ - /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, - /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, - /* 0x04 */ fpADD_IR_INIT, fpSUB_IR_INIT, - /* 0x06 */ fpMUL_IR_INIT, fpDIV_IR_INIT, - /* 0x00 */ fpMOD_IR_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x0a */ fpEQU_IR_INIT, fpNEQ_IR_INIT, - /* 0x0c */ fpLT_IR_INIT, fpGTE_IR_INIT, - /* 0x0e */ fpGT_IR_INIT, fpLTE_IR_INIT, - /* 0x10 */ fpNEG_R_INIT, fpABS_R_INIT, - /* 0x12 */ fpSQR_R_INIT, fpSQRT_R_INIT, - /* 0x14 */ fpSIN_R_INIT, fpCOS_R_INIT, - /* 0x16 */ fpATAN_R_INIT, fpLN_R_INIT, - /* 0x18 */ fpEXP_R_INIT -}; - -static const struct regm_builtin_s g_rgIiFopBuiltIns[MAX_FOP] = -{ - /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, - /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, - /* 0x04 */ fpADD_II_INIT, fpSUB_II_INIT, - /* 0x06 */ fpMUL_II_INIT, fpDIV_II_INIT, - /* 0x00 */ fpMOD_II_INIT, ILLEGAL_BUILTIN_INIT, - /* 0x0a */ fpEQU_II_INIT, fpNEQ_II_INIT, - /* 0x0c */ fpLT_II_INIT, fpGTE_II_INIT, - /* 0x0e */ fpGT_II_INIT, fpLTE_II_INIT, - /* 0x10 */ fpNEG_I_INIT, fpABS_I_INIT, - /* 0x12 */ fpSQR_I_INIT, fpSQRT_I_INIT, - /* 0x14 */ fpSIN_I_INIT, fpCOS_I_INIT, - /* 0x16 */ fpATAN_I_INIT, fpLN_I_INIT, - /* 0x18 */ fpEXP_I_INIT -}; - -static const struct regm_builtin_s *g_prgFopBuiltIns[4] = -{ - /* Real - Real */ g_rgRrFopBuiltIns, - /* Integer - Real */ g_rgRiFopBuiltIns, - /* Real - Ingeter */ g_rgIrFopBuiltIns, - /* Integer - Integer */ g_rgIiFopBuiltIns -}; - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/***********************************************************************/ - -static void regm_NoOperation(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, struct procdata_s *pNode) -{ - TRACE(stderr, "[regm_NoOperation]"); - - /* Do nothing */ -} - -/***********************************************************************/ -/* These pcodes are all binary operations in the sense that they take - * one input and produce one output: - * - * INPUT: TOS(0) - * OUTPUT: TOS(0) - * Stack is unchanged. - */ - -static void regm_UnaryOperation(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, struct procdata_s *pNode) -{ - uint32 dwUnaryRegister = MKCCREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwCcRegister = MKCCREG(g_dwStackOffset); - - TRACE(stderr, "[regm_UnaryOperation]"); - - switch (GETOP(pOpCode)) - { - case oABS: - regm_GenerateForm1ICc(rCMPI, dwUnaryRegister, 0, dwCcRegister); - regm_GenerateForm4ICc(rBGTE, 2, dwCcRegister); - - default: - regm_GenerateForm3I(pEntry->chOpCode, dwUnaryRegister, - dwUnaryRegister, pEntry->chImmediate); - break; - } -} - -/***********************************************************************/ -/* These pcodes are all binary operations in the sense that they take - * two input: - * - * INPUT: TOS(0), TOS(-1) - * OUTPUT: TOS(0) - * Stack reduced by one. - * - * These all generate form 3r instructions: - */ - -static void regm_BinaryOperation(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwROperand2 = MKREG(g_dwStackOffset - 2*sINT_SIZE); - uint32 dwRDest = dwROperand2; - - TRACE(stderr, "[regm_BinaryOperation]"); - - /* Generate the binary operation */ - - regm_GenerateForm3R(pEntry->chOpCode, dwRDest, dwROperand1, dwROperand2); - - /* Reduce stack */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* These pcodes are all boolean unary operations in the sense that - * the pcode form takes one input and generates one output: - * - * INPUT: TOS(0) - * OUTPUT: TOS(0) - * Stack unchanged - * - * The complication is that the resulting boolean is not represented by - * data in the register model but, rather, as a condition code setting. - * For now we can, however, force a large number of condition code - * registers; during a later fixup pass, we can force this to a single - * condition code register. - */ - -static void regm_CompareVsZero(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwUnaryRegister = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwCcRegister = MKCCREG(g_dwStackOffset); - - TRACE(stderr, "[regm_CompareVsZero]"); - - regm_GenerateForm1ICc(rCMPI, dwUnaryRegister, 0, dwCcRegister); - regm_GenerateForm2I(rMOVI, dwUnaryRegister, 0); - regm_GenerateForm4ICc(pEntry->chOpCode, 2, dwCcRegister); - regm_GenerateForm2I(rMOVI, dwUnaryRegister, 1); -} - -/***********************************************************************/ -/* These pcodes are all boolean binary operations in the sense that - * the pcode form takes two inputs and generates one output: - * - * INPUT: TOS(0), TOS(-1) - * OUTPUT: TOS(0) - * Stack reduced by one. - * - * The complication is that the resulting boolean not represented by - * data in the register model but, rather, as a condition code setting. - * For now we can, however, force a large number of condition code - * registers; during a later fixup pass, we can force this to a single - * condition code register. - */ - -static void regm_BinaryComparison(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwROperand2 = MKREG(g_dwStackOffset - 2*sINT_SIZE); - uint32 dwRDest = dwROperand2; - uint32 dwCcRegister = MKCCREG(g_dwStackOffset); - - TRACE(stderr, "[regm_BinaryComparison]"); - - - switch (GETOP(pOpCode)) - { - case oBIT: - regm_GenerateForm3R(rAND, dwRDest, dwROperand1, dwROperand2); - regm_GenerateForm1ICc(rCMPI, dwRDest, 0, dwCcRegister); - break; - - default: - regm_GenerateForm1RCc(rCMP, dwROperand1, dwROperand2, dwCcRegister); - break; - } - - regm_GenerateForm2I(rMOVI, dwRDest, 0); - regm_GenerateForm4ICc(pEntry->chOpCode, 2, dwCcRegister); - regm_GenerateForm2I(rMOVI, dwRDest, 1); - - /* Reduce stack */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* Load from the address on the stack. Stack is unchanged */ - -static void regm_LoadImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRDest = dwROperand1; - - TRACE(stderr, "[regm_LoadImmediate]"); - - /* Use the immediate value as an index against the SPB/LSP */ - - regm_GenerateForm3R(pEntry->chOpCode, dwRDest, dwROperand1, - MKSPECIAL(pEntry->chSpecial)); -} - -/***********************************************************************/ -/* Generic load multiple logic */ - -static void regm_LoadMultiple(uint32 dwRDest, uint32 dwRSrc) -{ - TRACE(stderr, "[regm_LoadMultiple]"); - - if (g_bRegisterCountValid) - { - regm_GenerateForm3I(rLDM, dwRDest, dwRSrc, g_dwRegisterCount); - - /* Adjust the stack for the g_dwRegisterCount values added to the - * stack. - */ - - g_dwStackOffset += g_dwRegisterCount * sINT_SIZE; - g_bRegisterCountValid = 0; - } - else - { - fatal(ePOFFCONFUSION); - } -} - -/***********************************************************************/ -/* SPB/LSP relative source offset is on the stack. Stack increase determined - * by content of DC register. - */ - -static void regm_LoadMultipleImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRDest = dwRSrc; - - TRACE(stderr, "[regm_LoadMultipleImmediate]"); - - /* Adjust the src for the SPB/LSP value and generate the multiple load */ - - regm_GenerateForm3R(rADD, dwRSrc, dwRSrc, MKSPECIAL(pEntry->chSpecial)); - regm_LoadMultiple(dwRSrc, dwRDest); - - /* Stack will be increased by an amount determined by DC in - * regm_LoadMultiple. However, we need to also account for the - * immediate stack value that we consume here. - */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* Store value on stack to address on stack. Stack is reduced by two */ - -static void regm_StoreImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwROperand1 = MKREG(g_dwStackOffset - 2*sINT_SIZE); - - TRACE(stderr, "[regm_StoreImmediate]"); - - /* Use the immediate value as an index against the SPB/LSP */ - - regm_GenerateForm3R(pEntry->chOpCode, dwRSrc, dwROperand1, - MKSPECIAL(pEntry->chSpecial)); - - /* Reduce stack */ - - g_dwStackOffset -= 2*sINT_SIZE; -} - -/***********************************************************************/ -/* Generic store multiple logic */ - -static void regm_StoreMultiple(uint32 dwRDest, uint32 dwRSrc) -{ - TRACE(stderr, "[regm_StoreMultiple]"); - - if (g_bRegisterCountValid) - { - regm_GenerateForm3I(rSTM, dwRSrc, dwRDest, g_dwRegisterCount); - - /* Adjust the stack for the g_dwRegisterCount values added to the - * stack. - */ - - g_dwStackOffset -= g_dwRegisterCount * sINT_SIZE; - g_bRegisterCountValid = 0; - } - else - { - fatal(ePOFFCONFUSION); - } -} - -/***********************************************************************/ -/* Store multiple values on stack to address on stack. Stack is reduced - * by an amount determined by the content of DC. - */ - -static void regm_StoreMultipleImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRDest = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRSrc = MKREG(g_dwStackOffset - (g_dwRegisterCount + 1)*sINT_SIZE); - - TRACE(stderr, "[regm_StoreMultipleImmediate]"); - - /* Adjust the src for the SPB/LSP value and generate the multiple load */ - - regm_GenerateForm3R(rADD, dwRDest, dwRDest, MKSPECIAL(pEntry->chSpecial)); - regm_StoreMultiple(dwRSrc, dwRDest); - - /* Stack will be increased by an amount determined by DC in - * regm_StoreMultiple. However, we need to also account for the - * immediate stack value that we consume here. - */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* Duplicate the TOS. stack increases by one */ - -static void regm_Duplicate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRDest = MKREG(g_dwStackOffset); - - TRACE(stderr, "[regm_Duplicate]"); - - /* Generate the binary operation */ - - regm_GenerateForm2R(rMOV, dwRDest, dwROperand1); - - /* Increment the stack */ - - g_dwStackOffset += sINT_SIZE; -} - -/***********************************************************************/ -/* Put the immediate value at the top of the stack. Increment stack */ - -static void regm_PushImmediate(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRDest = g_dwStackOffset; - - TRACE(stderr, "[regm_PushImmediate]"); - - /* The value may be too large to represent with a MOVI, but we'll handle - * that later. - */ - - regm_GenerateForm2I(rMOVI, dwRDest, GETARG(pOpCode)); - - /* Increment the stack */ - - g_dwStackOffset += sINT_SIZE; -} - -/***********************************************************************/ -/* Push the special register onto the stack. Stack increments by one */ - -static void regm_PushSpecial(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRDest = g_dwStackOffset; - - TRACE(stderr, "[regm_PushSpecial]"); - - regm_GenerateForm2R(rMOV, dwRDest, MKSPECIAL(pEntry->chSpecial)); - - /* Increment the stack */ - - g_dwStackOffset += sINT_SIZE; -} - -/***********************************************************************/ -/* Pop the TOS into the special register. Stack decrements by one */ - -static void regm_PopSpecial(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); - - TRACE(stderr, "[regm_PopSpecial]"); - - regm_GenerateForm2R(rMOV, MKSPECIAL(pEntry->chSpecial), dwROperand1); - - /* Decrement the stack */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* Save the immediate value in the data count register */ - -static void regm_SetDataCount(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - /* We don't acutally use the DC register. It is an artifact just - * get here. We save the byte count as a even number of registers. - */ - - g_dwRegisterCount = (GETARG(pOpCode) + 3) >> 2; - g_bRegisterCountValid = 1; -} - -/***********************************************************************/ - -static void regm_Return(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - TRACE(stderr, "[regm_Return]"); - - /* This should have been processed by the prologue/epilogue logic */ - - fatal(ePOFFCONFUSION); -} - -/***********************************************************************/ -/* Load at offset from SPB/LSP. Stack increases by one */ - -static void regm_LoadOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRDest = g_dwStackOffset; - - TRACE(stderr, "[regm_LoadOffset]"); - - /* Use the immediate value as an index against the SPB/LSP */ - - regm_GenerateForm3I(pEntry->chOpCode, dwRDest, MKSPECIAL(pEntry->chSpecial), - GETARG(pOpCode) >> pEntry->chImmediate); - - /* Increment the stack */ - - g_dwStackOffset += sINT_SIZE; -} - -/***********************************************************************/ -/* Load multiple registgers at offset from SPB/LSP. Stack increase depends - * on value in DC (only) - */ - -static void regm_LoadMultipleOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRSrc = MKREG(g_dwStackOffset); - uint32 dwRDest = dwRSrc; - - TRACE(stderr, "[regm_LoadMultipleOffset]"); - - regm_GenerateForm3R(rADD, dwRSrc, MKSPECIAL(pEntry->chSpecial), - GETARG(pOpCode)); - regm_LoadMultiple(dwRSrc, dwRDest); -} - -/***********************************************************************/ -/* Store at offset from SPB/LSP. Stack decreases by one */ - -static void regm_StoreOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); - - TRACE(stderr, "[regm_StoreOffset]"); - - /* Use the immediate value as an index against the SPB/LSP */ - - regm_GenerateForm3I(pEntry->chOpCode, dwRSrc, - MKSPECIAL(pEntry->chSpecial), - GETARG(pOpCode) >> pEntry->chImmediate); - - /* Decrement the stack */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* Store multiple at offset from SPB/LSP. Stack decreases an amount - * determined by the content of the DC regsiter. - */ - -static void regm_StoreMultipleOffset(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRSrc = MKREG(g_dwStackOffset - g_dwRegisterCount*sINT_SIZE); - uint32 dwRDest; - - TRACE(stderr, "[regm_StoreMultipleOffset]"); - - regm_GenerateForm3R(rADD, dwRDest, MKSPECIAL(pEntry->chSpecial), - GETARG(pOpCode)); - regm_StoreMultiple(dwRSrc, dwRDest); -} - -/***********************************************************************/ -/* Load value using index on stack + argument + SPB/LSP. Stack is unchanged */ - -static void regm_LoadIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRDest = dwRIndex; - - TRACE(stderr, "[regm_LoadIndexed]"); - - /* Add the SPB/LSP to the index to make it relative to the stack, - * then use this with the immediate values to obtain the data. - */ - - regm_GenerateForm3R(rADD, dwRIndex, dwRIndex, - MKSPECIAL(pEntry->chSpecial)); - regm_GenerateForm3I(pEntry->chOpCode, dwRDest, dwRDest, - GETARG(pOpCode) >> pEntry->chImmediate); -} - -/***********************************************************************/ -/* Load multiple values using index on stack + argument + SPB/LSP. Stack - * will increase my an amount that depends on the contents of DC. - */ - -static void regm_LoadMultipleIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRSrc = dwRIndex; - uint32 dwRDest = dwRIndex; - - TRACE(stderr, "[regm_LoadMultipleIndexed]"); - - /* Add the SPB/LSP to the index to make it relative to the stack, - * add the offset, then generate the multple load. - */ - - regm_GenerateForm3R(rADD, dwRSrc, dwRIndex, - MKSPECIAL(pEntry->chSpecial)); - regm_GenerateForm3I(rADDI, dwRSrc, dwRSrc, GETARG(pOpCode)); - regm_LoadMultiple(dwRSrc, dwRDest); - - /* Stack will be increased by an amount determined by DC in - * regm_LoadMultiple. However, we need to also account for the - * index stack value that we consume here. - */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* Store value at TOS to index + offset + SPB/LSP. Stack decreases by two */ - -static void regm_StoreIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRIndex = MKREG(g_dwStackOffset - 2*sINT_SIZE); - - TRACE(stderr, "[regm_StoreIndexed]"); - - /* Add the LSP to the index to make it relative to the stack, - * then use this with the immediate values to obtain the data. - */ - - regm_GenerateForm3R(rADD, dwRIndex, dwRIndex, - MKSPECIAL(pEntry->chSpecial)); - regm_GenerateForm3I(pEntry->chOpCode, dwRSrc, dwRIndex, - GETARG(pOpCode) >> pEntry->chImmediate); - - /* Decrement the stack */ - - g_dwStackOffset -= 2*sINT_SIZE; -} - -/***********************************************************************/ -/* Store values at TOS to index + offset + SPB/LSP. Stack decreases by - * amount determined by the content of the DC register. - */ - -static void regm_StoreMultipleIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRSrc = MKREG(g_dwStackOffset - (g_dwRegisterCount + 1)*sINT_SIZE); - uint32 dwRDest; - - TRACE(stderr, "[regm_StoreMultipleIndexed]"); - - /* Adjust the src for the SPB/LSP value and generate the multiple load */ - - regm_GenerateForm3R(rADD, dwRDest, dwRIndex, - MKSPECIAL(pEntry->chSpecial)); - regm_GenerateForm3I(rADDI, dwRDest, dwRDest, GETARG(pOpCode)); - regm_StoreMultiple(dwRSrc, dwRDest); - - /* Stack will be increased by an amount determined by DC in - * regm_StoreMultiple. However, we need to also account for the - * immediate stack value that we consume here. - */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* These pcodes are all conditional branch operations. The pcode form - * takes one input (that is compared with zero) and branches based - * the result. The stack is decremented by one. - */ - -static void regm_ConditionalBranchVsZero(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwUnaryRegister = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwCcRegister = MKCCREG(g_dwStackOffset); - - TRACE(stderr, "[regm_ConditionalBranchVsZero]"); - - - regm_GenerateForm1ICc(rCMPI, dwUnaryRegister, 0, dwCcRegister); - regm_GenerateForm4ICc(pEntry->chOpCode, GETARG(pOpCode), dwCcRegister); - - /* Decrement the stack */ - - g_dwStackOffset -= sINT_SIZE; -} - -/***********************************************************************/ -/* These pcodes are all conditional branch operations. The pcode form - * takes two inputs that are compared. The pcode branches on the result - * of the comparison. The stack is reduced by two. - */ - -static void regm_ConditionalBranchBinary(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwROperand2 = MKREG(g_dwStackOffset - 2*sINT_SIZE); - uint32 dwCcRegister = MKCCREG(g_dwStackOffset); - - TRACE(stderr, "[regm_BinaryComparison]"); - - /* Generate the compare and branch */ - - regm_GenerateForm1RCc(rCMP, dwROperand1, dwROperand2, dwCcRegister); - regm_GenerateForm4ICc(pEntry->chOpCode, GETARG(pOpCode), dwCcRegister); - - /* Reduce stack */ - - g_dwStackOffset -= 2*sINT_SIZE; -} - -/***********************************************************************/ -/* Branch unconditionally. The stack is not changed */ - -static void regm_UnconditionalBranch(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - TRACE(stderr, "[regm_UnconditionalBranch]"); - regm_GenerateForm4I(rB, GETARG(pOpCode)); -} - -/***********************************************************************/ -/* Add constant value to special register. Stack does not change */ - -static void regm_IncrementSpecial(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - sint32 dwIncrement = (sint32)(GETOP(pOpCode)); - uint32 dwRSpecial = MKSPECIAL(pEntry->chSpecial); - TRACE(stderr, "[regm_IncrementSpecial]"); - - /* The value may be too large to represent with a MOVI, but we'll handle - * that later. - */ - - if (dwIncrement < 0) - { - regm_GenerateForm3I(rSUBI, dwRSpecial, dwRSpecial, -dwIncrement); - } - else if (dwIncrement > 0) - { - regm_GenerateForm3I(rADDI, dwRSpecial, dwRSpecial, dwIncrement); - } - - if (pEntry->chSpecial == SP) - { - g_dwStackOffset += dwIncrement; - } -} - -/***********************************************************************/ -/* Load address at offset from special register. Stack increases by one */ - -static void regm_LoadAddress(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRDest = g_dwStackOffset; - - TRACE(stderr, "[regm_LoadAddress]"); - - /* Use the immediate value as an index against the SPB/LSP */ - - regm_GenerateForm3I(rADD, dwRDest, MKSPECIAL(pEntry->chSpecial), - GETARG(pOpCode)); - - /* Increment the stack */ - - g_dwStackOffset += sINT_SIZE; -} - -/***********************************************************************/ -/* Load address at indexed offset from special register. Stack is unchanged */ - -static void regm_LoadAddressIndexed(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - uint32 dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); - uint32 dwRDest = dwRIndex; - - TRACE(stderr, "[regm_LoadAddressIndexed]"); - - /* Add the LSP or SPB to the index to make it relative to the stack, - * then use this with the immediate values to obtain the data. - */ - - regm_GenerateForm3R(rADD, dwRIndex, dwRIndex, - MKSPECIAL(pEntry->chSpecial)); - regm_GenerateForm3I(rADD, dwRDest, dwRIndex, GETARG(pOpCode)); -} - -/***********************************************************************/ - -static void regm_SetupOutArgs(uint32 nParms, const uint32 *pwArgSize) -{ - int nArgRegs; - sint32 dwOffset; - int i; - - for (i = 0, nArgRegs = 0; i < nParms; i++) - { - nArgRegs += (pwArgSize[i] + 3) >> 2; - } - - /* Emit move instructions to handle each */ - - dwOffset = g_dwStackOffset - sINT_SIZE; - for (i = 0; i < nArgRegs; i++) - { - uint32 dwDest = MKOUTARG(i); - uint32 dwSrc = MKREG(dwOffset); - - regm_GenerateForm2R(rMOV, dwDest, dwSrc); - dwOffset -= sINT_SIZE; - } -} - -/***********************************************************************/ - -static void regm_MapInRet(uint32 wRetSize) -{ - int nRetRegs; - sint32 dwOffset; - int i; - - /* Get the number of registers that are returned */ - - nRetRegs += (wRetSize + 3) >> 2; - - /* Emit move instructions to handle each */ -#warning "This offset is not correct" - dwOffset = g_dwStackOffset - sINT_SIZE; - for (i = 0; i < nRetRegs; i++) - { - uint32 dwSrc = MKINRET(i); - uint32 dwDest = MKREG(dwOffset); - - regm_GenerateForm2R(rMOV, dwDest, dwSrc); - dwOffset -= sINT_SIZE; - } -} - -/***********************************************************************/ - -static void regm_PCal(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - poffLibDebugFuncInfo_t *pFuncInfo = pNode->pFuncInfo; - - TRACE(stderr, "[regm_PCal]"); - - if (!pFuncInfo) - { - fatal(ePOFFCONFUSION); - } - - /* Map the "output" parameter stack to a set of "output" argument - * registers. - */ - - regm_SetupOutArgs(pFuncInfo->nparms, pFuncInfo->argsize); - - regm_GenerateForm3I(rADDI, MKSPECIAL(SP), MKSPECIAL(SP), 3*sINT_SIZE); - regm_GenerateForm3I(rST, MKSPECIAL(LSP), MKSPECIAL(SP), -3); - regm_GenerateForm3I(rST, MKSPECIAL(BRG), MKSPECIAL(SP), -2); - regm_GenerateForm4I(rBL, GETARG(pOpCode)); - -#warning "This is in the wrong place" - regm_MapInRet(pFuncInfo->retsize); - - /* Increment the stack */ - - g_dwStackOffset += 3*sINT_SIZE; -} - -/***********************************************************************/ - -static void regm_SysIo(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - const struct regm_builtin_s *pBuiltIn; - uint32 xop; - - TRACE(stderr, "[regm_SysIo]"); - - /* Get the function information for this sysio xop */ - - xop = GETARG(pOpCode); - if (xop >= MAX_XOP) - { - fatal(ePOFFCONFUSION); - } - - pBuiltIn = &g_rgSysIoBuiltIns[xop]; - - /* Map the "output" parameter stack to a set of "output" argument - * registers. - */ - - regm_SetupOutArgs(pBuiltIn->nParms, pBuiltIn->wArgSize); - - /* Generate a call to the runtime library */ - -#warning "Not implemented" - - /* Handled returned values */ - - regm_MapInRet(pBuiltIn->wRetSize); -} - -/***********************************************************************/ - -static void regm_LibCall(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - const struct regm_builtin_s *pBuiltIn; - uint32 lbop; - - TRACE(stderr, "[regm_LibCall]"); - - /* Get the function information for this library op */ - - lbop = GETARG(pOpCode); - if (lbop >= MAX_LBOP) - { - fatal(ePOFFCONFUSION); - } - - pBuiltIn = &g_rgLibCallBuiltIns[lbop]; - - /* Map the "output" parameter stack to a set of "output" argument - * registers. - */ - - regm_SetupOutArgs(pBuiltIn->nParms, pBuiltIn->wArgSize); - - /* Generate a call to the runtime library */ - -#warning "Not implemented" - - /* Handled returned values */ - - regm_MapInRet(pBuiltIn->wRetSize); -} - -/***********************************************************************/ - -static void regm_Float(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - static const struct regm_builtin_s *pFopBuiltIns; - const struct regm_builtin_s *pBuiltIn; - uint32 foptab; - uint32 fop; - - TRACE(stderr, "[regm_FLoat]"); - - /* Select the correct table for the builtin */ - - foptab = (GETARG(pOpCode) & ~fpMASK) >> fpSHIFT; - pFopBuiltIns = g_prgFopBuiltIns[foptab]; - - /* Select the correct function from the table for this floating - * point operation. - */ - - fop = GETARG(pOpCode) & fpMASK; - if (fop >= MAX_FOP) - { - fatal(ePOFFCONFUSION); - } - pBuiltIn = &pFopBuiltIns[fop]; - - /* Map the "output" parameter stack to a set of "output" argument - * registers. - */ - - regm_SetupOutArgs(pBuiltIn->nParms, pBuiltIn->wArgSize); - - /* Generate a call to the runtime library */ - -#warning "Not implemented" - - /* Handled returned values */ - - regm_MapInRet(pBuiltIn->wRetSize); -} - -/***********************************************************************/ - -static void regm_IllegalPCode(const struct regm_opmap_s *pEntry, - OPTYPE *pOpCode, - struct procdata_s *pNode) -{ - TRACE(stderr, "[regm_IllegalPCode]"); - fatal(eILLEGALOPCODE); -} - -/***********************************************************************/ - -static void regm_GenerateRegm(struct procdata_s *pNode, void *pvArg) -{ - sint32 dwFrameSize = 0; - int i, j; - - TRACE(stderr, "[regm_GenerateRegm]"); - - /* Analyze the proc/func prologue */ - - i = 0; j = pNode->nPCodes; - if (GETOP(&pNode->pPCode[0]) == oINDS) - { - dwFrameSize = GETARG(&pNode->pPCode[0]); - i++; j--; - } - regm_GeneratePrologue(dwFrameSize); - - /* Set the initial stack offset. Parameters will look like - * negative offsets; local stack will look positive. - */ - - g_dwStackOffset = dwFrameSize; - - /* Generate regm code for each p-code */ - - for (; i < j; i++) - { - const struct regm_opmap_s *rgOpMap; - ubyte chOpCode = GETOP(&pNode->pPCode[i]); - - /* Select the right decode table */ - - if ((chOpCode & o32) != 0) - { - rgOpMap = vrgOpMap2; - chOpCode &= ~o32; - } - else - { - rgOpMap = vrgOpMap1; - } - - /* Make sure that the table index is within range */ - - if (chOpCode > 63) - { - fatal(eBADSHORTINT); - } - - /* Perform the opcode mapping */ - - rgOpMap->pMapper(rgOpMap, &pNode->pPCode[i], pNode); - } - - /* If a frame was obtained at the beginning, make sure that - * there is matching frame release logic at the end. - */ - - if (dwFrameSize > 0) - { - if ((GETOP(&pNode->pPCode[i]) != oINDS) || - (dwFrameSize != -(sint32)GETARG(&pNode->pPCode[i]))) - { - fatal(ePOFFCONFUSION); - } - i++; - } - - /* Analyze the proc/func epilogue */ - - if ((GETOP(&pNode->pPCode[i]) != oRET) && - (GETOP(&pNode->pPCode[i]) != oEND)) - { - fatal(ePOFFCONFUSION); - } - regm_GenerateEpilogue(dwFrameSize); -} - -/***********************************************************************/ - -static int regm_Pass2Node(struct procdata_s *pNode, void *pvArg) -{ - TRACE(stderr, "[regm_Pass2Node]"); - - /* Generate code for each child of this proc/func block */ - - if (pNode->child) - { - (void)regm_ForEachChild(pNode->child, regm_Pass2Node, pvArg); - } - - /* Generate code for this node */ - - regm_GenerateRegm(pNode, pvArg); - - /* Does this node have a peer at the same level? If so, then - * do the same for its peer. - */ - - if (pNode->peer) - { - (void)regm_Pass2Node(pNode->peer, pvArg); - } - - return 0; -} - -/********************************************************************** - * Public Functions - **********************************************************************/ - -/***********************************************************************/ -/* Pass 2: Convert the buffered pcode to the basic register model with - * an indefinite number of registers (arguments, general, and special - * registers) and with 32-bit immediate size. - */ - -void regm_Pass2(poffHandle_t hPoff) -{ - TRACE(stderr, "[regm_Pass2]"); - - /* Initiate traversal at the root node */ - - (void)regm_Pass2Node(regm_GetRootNode(), NULL); -} - -/***********************************************************************/ - +/********************************************************************** + * regm_pass2.c + * Convert the buffered pcode to the basic register model with an + * indefinite number of registers (arguments, general, and special + * registers) and with 32-bit immediate size. + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + *********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include +#include +#include + +#include "keywords.h" +#include "pdefs.h" +#include "pxdefs.h" +#include "pfdefs.h" +#include "pedefs.h" +#include "pofflib.h" +#include "perr.h" + +#include "pinsn32.h" +#include "builtins.h" + +#include "regm.h" +#include "regm_tree.h" +#include "regm_registers2.h" +#include "regm_pass2.h" + +/************************************a********************************* + * Definitions + **********************************************************************/ + +/********************************************************************** + * Private Types + **********************************************************************/ + +struct regm_opmap_s; + +typedef void (*regm_mapper_t)(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, struct procdata_s *pNode); + +struct regm_opmap_s +{ + uint8_t chOpCode; + int8_t chImmediate; + int8_ chSpecial; + regm_mapper_t pMapper; +}; + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +static void regm_NoOperation(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_UnaryOperation(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_BinaryOperation(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_CompareVsZero(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_BinaryComparison(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_LoadImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_LoadMultiple(uint32_t dwRDest, uint32_t dwRSrc); +static void regm_LoadMultipleImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_StoreMultiple(uint32_t dwRDest, uint32_t dwRSrc); +static void regm_StoreImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_StoreMultipleImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_Duplicate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_PushImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_PopSpecial(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_SetDataCount(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_PushSpecial(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_Return(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_LoadOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_LoadMultipleOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_StoreOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_StoreMultipleOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_LoadIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, struct procdata_s *pNode); +static void regm_LoadMultipleIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_StoreIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, struct procdata_s *pNode); +static void regm_StoreMultipleIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_ConditionalBranchVsZero(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_ConditionalBranchBinary(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_UnconditionalBranch(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_IncrementSpecial(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_LoadAddress(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, struct procdata_s *pNode); +static void regm_LoadAddressIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_SetupOutArgs(uint32_t nParms, const uint32_t *pwArgSize); +static void regm_MapInRet(uint32_t wRetSize); +static void regm_PCal(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_SysIo(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_LibCall(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_Float(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); +static void regm_IllegalPCode(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode); + +static void regm_GenerateRegm(struct procdata_s *pNode, void *pvArg); +static int regm_Pass2Node(struct procdata_s *pNode, void *pvArg); + +/********************************************************************** + * Public Variables + **********************************************************************/ + +/* On the initialize passes, the register number will simply be the offset + * from the top of the stack. The following variable keeps trck of the + * stack offset. + */ + +uint32_t g_dwStackOffset; +uint32_t g_dwRegisterCount = 0; +int g_bRegisterCountValid = 0; + +/********************************************************************** + * Private Variables + **********************************************************************/ + +static const struct regm_opmap_s vrgOpMap1[64] = + { + /* 0x00: oNOP */ {0, 0, 0, regm_NoOperation}, + /* 0x01: oNEG */ {rRSBI, 0, 0, regm_UnaryOperation}, + /* 0x02: oABS */ {rRSB, 0, 0, regm_UnaryOperation}, + /* 0x03: oINC */ {rADDI, 1, 0, regm_UnaryOperation}, + /* 0x04: oDEC */ {rSUBI, 1, 0, regm_UnaryOperation}, + /* 0x05: oNOT */ {rMVN, 0, 0, regm_UnaryOperation}, + /* 0x06: oADD */ {rADD, 0, 0, regm_BinaryOperation}, + /* 0x07: oSUB */ {rSUB, 0, 0, regm_BinaryOperation}, + /* 0x08: oMUL */ {rMUL, 0, 0, regm_BinaryOperation}, + /* 0x09: oDIV */ {rDIV, 0, 0, regm_BinaryOperation}, + /* 0x0a: oMOD */ {rMOD, 0, 0, regm_BinaryOperation}, + /* 0x0b: oSLL */ {rSLL, 0, 0, regm_BinaryOperation}, + /* 0x0c: oSRL */ {rSRL, 0, 0, regm_BinaryOperation}, + /* 0x0d: oSRA */ {rSRA, 0, 0, regm_BinaryOperation}, + /* 0x0e: oOR */ {rOR, 0, 0, regm_BinaryOperation}, + /* 0x0f: oAND */ {rAND, 0, 0, regm_BinaryOperation}, + + /* 0x10: oEQUZ */ {rBEQ, 0, 0, regm_CompareVsZero}, + /* 0x11: oNEQZ */ {rBNE, 0, 0, regm_CompareVsZero}, + /* 0x12: oLTZ */ {rBLT, 0, 0, regm_CompareVsZero}, + /* 0x13: oGTEZ */ {rBGTE, 0, 0, regm_CompareVsZero}, + /* 0x14: oGTZ */ {rBGT, 0, 0, regm_CompareVsZero}, + /* 0x15: oLTEZ */ {rBLTE, 0, 0, regm_CompareVsZero}, + /* 0x16: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x17: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x18: oEQU */ {rBEQ, 0, 0, regm_BinaryComparison}, + /* 0x19: oNEQ */ {rBNE, 0, 0, regm_BinaryComparison}, + /* 0x1a: oLT */ {rBLT, 0, 0, regm_BinaryComparison}, + /* 0x1b: oGTE */ {rBGTE, 0, 0, regm_BinaryComparison}, + /* 0x1c: oGT */ {rBGT, 0, 0, regm_BinaryComparison}, + /* 0x1d: oLTE */ {rBLTE, 0, 0, regm_BinaryComparison}, + /* 0x1e: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x1f: oBIT */ {rBEQ, 0, 0, regm_BinaryComparison}, + + /* 0x20: oLDI */ {rLD, 2, SPB, regm_LoadImmediate}, + /* 0x21: oLDIH */ {rLDH, 1, SPB, regm_LoadImmediate}, + /* 0x22: oLDIB */ {rLDB, 0, SPB, regm_LoadImmediate}, + /* 0x23: oLDIM */ {0, 0, SPB, regm_LoadMultipleImmediate}, + /* 0x24: oSTI */ {rST, 2, SPB, regm_StoreImmediate}, + /* 0x25: oSTIH */ {rSTH, 1, SPB, regm_StoreImmediate}, + /* 0x26: oSTIB */ {rSTB, 0, SPB, regm_StoreImmediate}, + /* 0x27: oSTIM */ {0, 0, SPB, regm_StoreMultipleImmediate}, + /* 0x28: oDUP */ {0, 0, 0, regm_Duplicate}, + /* 0x17: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x2a: oPUSHS */ {0, 0, CSP, regm_PushSpecial}, + /* 0x2b: oPOPS */ {0, 0, CSP, regm_PopSpecial}, + /* 0x2c: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x2d: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x2e: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x2f: oRET */ {0, 0, 0, regm_Return}, + + /* 0x30: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x31: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x32: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x33: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x34: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x35: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x36: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x37: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x38: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x39: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x3a: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x3b: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x3c: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x3d: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x3e: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x3f: oEND */ {0, 0, 0, regm_Return} + }; + +static const struct regm_opmap_s vrgOpMap2[64] = + { + /* 0x80: oLD */ {rLD, 2, SPB, regm_LoadOffset}, + /* 0x81: oLDH */ {rLDH, 1, SPB, regm_LoadOffset}, + /* 0x82: oLDB */ {rLDB, 0, SPB, regm_LoadOffset}, + /* 0x83: oLDM */ {0, 0, SPB, regm_LoadMultipleOffset}, + /* 0x84: oST */ {rST, 2, SPB, regm_StoreOffset}, + /* 0x85: oSTH */ {rSTH, 1, SPB, regm_StoreOffset}, + /* 0x86: oSTB */ {rSTB, 0, SPB, regm_StoreOffset}, + /* 0x87: oSTM */ {0, 0, SPB, regm_StoreMultipleOffset}, + /* 0x88: oLDX */ {rLD, 2, SPB, regm_LoadIndexed}, + /* 0x89: oLDXH */ {rLDH, 1, SPB, regm_LoadIndexed}, + /* 0x8a: oLDXB */ {rLDB, 0, SPB, regm_LoadIndexed}, + /* 0x8b: oLDXM */ {0, 0, SPB, regm_LoadMultipleIndexed}, + /* 0x8c: oSTX */ {rST, 2, SPB, regm_StoreIndexed}, + /* 0x8d: oSTXH */ {rSTH, 1, SPB, regm_StoreIndexed}, + /* 0x8e: oSTXB */ {rSTB, 0, SPB, regm_StoreIndexed}, + /* 0x8f: oSTXM */ {0, 0, SPB, regm_StoreMultipleIndexed}, + + /* 0x90: oJEQUZ */ {rBEQ, 0, 0, regm_ConditionalBranchVsZero}, + /* 0x91: oJNEQZ */ {rBNE, 0, 0, regm_ConditionalBranchVsZero}, + /* 0x92: oJLTZ */ {rBLT, 0, 0, regm_ConditionalBranchVsZero}, + /* 0x93: oJGTEZ */ {rBGTE, 0, 0, regm_ConditionalBranchVsZero}, + /* 0x94: oJGTZ */ {rBGT, 0, 0, regm_ConditionalBranchVsZero}, + /* 0x95: oJLTEZ */ {rBLTE, 0, 0, regm_ConditionalBranchVsZero}, + /* 0x96: oJMP */ {rB, 0, 0, regm_UnconditionalBranch}, + /* 0x97: oPUSH */ {0, 0, 0, regm_PushImmediate}, + /* 0x98: oJEQU */ {rBEQ, 0, 0, regm_ConditionalBranchBinary}, + /* 0x99: oJNEQ */ {rBNE, 0, 0, regm_ConditionalBranchBinary}, + /* 0x9a: oJLT */ {rBLT, 0, 0, regm_ConditionalBranchBinary}, + /* 0x9b: oJGTE */ {rBGTE, 0, 0, regm_ConditionalBranchBinary}, + /* 0x9c: oJGT */ {rBGT, 0, 0, regm_ConditionalBranchBinary}, + /* 0x9d: oJLTE */ {rBLTE, 0, 0, regm_ConditionalBranchBinary}, + /* 0x9e: */ {0, 0, 0, regm_IllegalPCode}, + /* 0x9f: oINDS */ {0, 0, SP, regm_IncrementSpecial}, + + /* 0xa0: oLDS */ {rLD, 2, LSP, regm_LoadOffset}, + /* 0xa1: oLDSH */ {rLDH, 1, LSP, regm_LoadOffset}, + /* 0xa2: oLDSB */ {rLDB, 0, LSP, regm_LoadOffset}, + /* 0xa3: oLDSM */ {0, 0, LSP, regm_LoadMultipleOffset}, + /* 0xa4: oSTS */ {rST, 2, LSP, regm_StoreOffset}, + /* 0xa5: oSTSH */ {rSTH, 1, LSP, regm_StoreOffset}, + /* 0xa6: oSTSB */ {rSTB, 0, LSP, regm_StoreOffset}, + /* 0xa7: oSTSM */ {0, 0, LSP, regm_StoreMultipleOffset}, + /* 0xa8: oLDSX */ {rLD, 2, LSP, regm_LoadIndexed}, + /* 0xa9: oLDSXH */ {rLDH, 1, LSP, regm_LoadIndexed}, + /* 0xaa: oLDSXB */ {rLDB, 0, LSP, regm_LoadIndexed}, + /* 0xab: oLDSXM */ {0, 0, LSP, regm_LoadMultipleIndexed}, + /* 0xac: oSTSX */ {rST, 2, LSP, regm_StoreIndexed}, + /* 0xad: oSTSXH */ {rSTH, 1, LSP, regm_StoreIndexed}, + /* 0xae: oSTSXB */ {rSTB, 0, LSP, regm_StoreIndexed}, + /* 0xaf: oSTSXM */ {0, 0, LSP, regm_StoreMultipleIndexed}, + + /* 0xb0: oLA */ {0, 0, SPB, regm_LoadAddress}, + /* 0xb1: oLAS */ {0, 0, LSP, regm_LoadAddress}, + /* 0xb2: oLAC */ {0, 0, CSB, regm_LoadAddress}, + /* 0xb3: */ {0, 0, 0, regm_IllegalPCode}, + /* 0xb4: oLAX */ {0, 0, SPB, regm_LoadAddressIndexed}, + /* 0xb5: oLASX */ {0, 0, LSP, regm_LoadAddressIndexed}, + /* 0xb6: oSLSP */ {0, 0, LSP, regm_PopSpecial}, + /* 0xb7: oSDC */ {0, 0, DC, regm_SetDataCount}, + /* 0xb8: */ {0, 0, 0, regm_IllegalPCode}, + /* 0xb9: oPCAL */ {0, 0, 0, regm_PCal}, + /* 0xba: oSYSIO */ {0, 0, 0, regm_SysIo}, + /* 0xbb: oLIB */ {0, 0, 0, regm_LibCall}, + /* 0xbc: oFLOAT */ {0, 0, 0, regm_Float}, + /* 0xbd: oLABEL */ {0, 0, 0, regm_NoOperation}, + /* 0xbe: oINCLUDE*/ {0, 0, 0, regm_NoOperation}, + /* 0xbf: oLINE */ {0, 0, 0, regm_NoOperation} + }; + +static const struct regm_builtin_s g_rgSysIoBuiltIns[MAX_XOP] = +{ + /* 0x00 */ ILLEGAL_BUILTIN_INIT, xEOF_INIT, + /* 0x02 */ xEOLN_INIT, xRESET_INIT, + /* 0x04 */ xREWRITE_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x06 */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x08 */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x0a */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x0c */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x0e */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x10 */ xREADLN_INIT, xREAD_PAGE_INIT, + /* 0x12 */ xREAD_BINARY_INIT, xREAD_INT_INIT, + /* 0x14 */ xREAD_CHAR_INIT, xREAD_STRING_INIT, + /* 0x16 */ xREAD_REAL_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x18 */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x1a */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x1c */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x1e */ ILLEGAL_BUILTIN_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x20 */ xWRITELN_INIT, xWRITE_PAGE_INIT, + /* 0x22 */ xWRITE_BINARY_INIT, xWRITE_INT_INIT, + /* 0x24 */ xWRITE_CHAR_INIT, xWRITE_STRING_INIT, + /* 0x25 */ xWRITE_REAL_INIT +}; + +static const struct regm_builtin_s g_rgLibCallBuiltIns[MAX_LBOP] = +{ + /* 0x00 */ lbGETENV_INIT, lbSTR2STR_INIT, + /* 0x02 */ lbCSTR2STR_INIT, lbSTR2RSTR_INIT, + /* 0x04 */ lbCSTR2RSTR_INIT, lbVAL_INIT, + /* 0x06 */ lbMKSTK_INIT, lbMKSTKSTR_INIT, + /* 0x08 */ lbMKSTKC_INIT, lbSTRCAT_INIT, + /* 0x0a */ lbSTRCATC_INIT, lbSTRCMP_INIT +}; + +static const struct regm_builtin_s g_rgRrFopBuiltIns[MAX_FOP] = +{ + /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, + /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, + /* 0x04 */ fpADD_RR_INIT, fpSUB_RR_INIT, + /* 0x06 */ fpMUL_RR_INIT, fpDIV_RR_INIT, + /* 0x00 */ fpMOD_RR_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x0a */ fpEQU_RR_INIT, fpNEQ_RR_INIT, + /* 0x0c */ fpLT_RR_INIT, fpGTE_RR_INIT, + /* 0x0e */ fpGT_RR_INIT, fpLTE_RR_INIT, + /* 0x10 */ fpNEG_R_INIT, fpABS_R_INIT, + /* 0x12 */ fpSQR_R_INIT, fpSQRT_R_INIT, + /* 0x14 */ fpSIN_R_INIT, fpCOS_R_INIT, + /* 0x16 */ fpATAN_R_INIT, fpLN_R_INIT, + /* 0x18 */ fpEXP_R_INIT +}; + +static const struct regm_builtin_s g_rgRiFopBuiltIns[MAX_FOP] = +{ + /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, + /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, + /* 0x04 */ fpADD_RI_INIT, fpSUB_RI_INIT, + /* 0x06 */ fpMUL_RI_INIT, fpDIV_RI_INIT, + /* 0x00 */ fpMOD_RI_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x0a */ fpEQU_RI_INIT, fpNEQ_RI_INIT, + /* 0x0c */ fpLT_RI_INIT, fpGTE_RI_INIT, + /* 0x0e */ fpGT_RI_INIT, fpLTE_RI_INIT, + /* 0x10 */ fpNEG_I_INIT, fpABS_I_INIT, + /* 0x12 */ fpSQR_I_INIT, fpSQRT_I_INIT, + /* 0x14 */ fpSIN_I_INIT, fpCOS_I_INIT, + /* 0x16 */ fpATAN_I_INIT, fpLN_I_INIT, + /* 0x18 */ fpEXP_I_INIT +}; + +static const struct regm_builtin_s g_rgIrFopBuiltIns[MAX_FOP] = +{ + /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, + /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, + /* 0x04 */ fpADD_IR_INIT, fpSUB_IR_INIT, + /* 0x06 */ fpMUL_IR_INIT, fpDIV_IR_INIT, + /* 0x00 */ fpMOD_IR_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x0a */ fpEQU_IR_INIT, fpNEQ_IR_INIT, + /* 0x0c */ fpLT_IR_INIT, fpGTE_IR_INIT, + /* 0x0e */ fpGT_IR_INIT, fpLTE_IR_INIT, + /* 0x10 */ fpNEG_R_INIT, fpABS_R_INIT, + /* 0x12 */ fpSQR_R_INIT, fpSQRT_R_INIT, + /* 0x14 */ fpSIN_R_INIT, fpCOS_R_INIT, + /* 0x16 */ fpATAN_R_INIT, fpLN_R_INIT, + /* 0x18 */ fpEXP_R_INIT +}; + +static const struct regm_builtin_s g_rgIiFopBuiltIns[MAX_FOP] = +{ + /* 0x00 */ ILLEGAL_BUILTIN_INIT, fpFLOAT_INIT, + /* 0x02 */ fpTRUNC_INIT, fpROUND_INIT, + /* 0x04 */ fpADD_II_INIT, fpSUB_II_INIT, + /* 0x06 */ fpMUL_II_INIT, fpDIV_II_INIT, + /* 0x00 */ fpMOD_II_INIT, ILLEGAL_BUILTIN_INIT, + /* 0x0a */ fpEQU_II_INIT, fpNEQ_II_INIT, + /* 0x0c */ fpLT_II_INIT, fpGTE_II_INIT, + /* 0x0e */ fpGT_II_INIT, fpLTE_II_INIT, + /* 0x10 */ fpNEG_I_INIT, fpABS_I_INIT, + /* 0x12 */ fpSQR_I_INIT, fpSQRT_I_INIT, + /* 0x14 */ fpSIN_I_INIT, fpCOS_I_INIT, + /* 0x16 */ fpATAN_I_INIT, fpLN_I_INIT, + /* 0x18 */ fpEXP_I_INIT +}; + +static const struct regm_builtin_s *g_prgFopBuiltIns[4] = +{ + /* Real - Real */ g_rgRrFopBuiltIns, + /* Integer - Real */ g_rgRiFopBuiltIns, + /* Real - Ingeter */ g_rgIrFopBuiltIns, + /* Integer - Integer */ g_rgIiFopBuiltIns +}; + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/***********************************************************************/ + +static void regm_NoOperation(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, struct procdata_s *pNode) +{ + TRACE(stderr, "[regm_NoOperation]"); + + /* Do nothing */ +} + +/***********************************************************************/ +/* These pcodes are all binary operations in the sense that they take + * one input and produce one output: + * + * INPUT: TOS(0) + * OUTPUT: TOS(0) + * Stack is unchanged. + */ + +static void regm_UnaryOperation(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, struct procdata_s *pNode) +{ + uint32_t dwUnaryRegister = MKCCREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwCcRegister = MKCCREG(g_dwStackOffset); + + TRACE(stderr, "[regm_UnaryOperation]"); + + switch (GETOP(pOpCode)) + { + case oABS: + regm_GenerateForm1ICc(rCMPI, dwUnaryRegister, 0, dwCcRegister); + regm_GenerateForm4ICc(rBGTE, 2, dwCcRegister); + + default: + regm_GenerateForm3I(pEntry->chOpCode, dwUnaryRegister, + dwUnaryRegister, pEntry->chImmediate); + break; + } +} + +/***********************************************************************/ +/* These pcodes are all binary operations in the sense that they take + * two input: + * + * INPUT: TOS(0), TOS(-1) + * OUTPUT: TOS(0) + * Stack reduced by one. + * + * These all generate form 3r instructions: + */ + +static void regm_BinaryOperation(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwROperand2 = MKREG(g_dwStackOffset - 2*sINT_SIZE); + uint32_t dwRDest = dwROperand2; + + TRACE(stderr, "[regm_BinaryOperation]"); + + /* Generate the binary operation */ + + regm_GenerateForm3R(pEntry->chOpCode, dwRDest, dwROperand1, dwROperand2); + + /* Reduce stack */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* These pcodes are all boolean unary operations in the sense that + * the pcode form takes one input and generates one output: + * + * INPUT: TOS(0) + * OUTPUT: TOS(0) + * Stack unchanged + * + * The complication is that the resulting boolean is not represented by + * data in the register model but, rather, as a condition code setting. + * For now we can, however, force a large number of condition code + * registers; during a later fixup pass, we can force this to a single + * condition code register. + */ + +static void regm_CompareVsZero(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwUnaryRegister = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwCcRegister = MKCCREG(g_dwStackOffset); + + TRACE(stderr, "[regm_CompareVsZero]"); + + regm_GenerateForm1ICc(rCMPI, dwUnaryRegister, 0, dwCcRegister); + regm_GenerateForm2I(rMOVI, dwUnaryRegister, 0); + regm_GenerateForm4ICc(pEntry->chOpCode, 2, dwCcRegister); + regm_GenerateForm2I(rMOVI, dwUnaryRegister, 1); +} + +/***********************************************************************/ +/* These pcodes are all boolean binary operations in the sense that + * the pcode form takes two inputs and generates one output: + * + * INPUT: TOS(0), TOS(-1) + * OUTPUT: TOS(0) + * Stack reduced by one. + * + * The complication is that the resulting boolean not represented by + * data in the register model but, rather, as a condition code setting. + * For now we can, however, force a large number of condition code + * registers; during a later fixup pass, we can force this to a single + * condition code register. + */ + +static void regm_BinaryComparison(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwROperand2 = MKREG(g_dwStackOffset - 2*sINT_SIZE); + uint32_t dwRDest = dwROperand2; + uint32_t dwCcRegister = MKCCREG(g_dwStackOffset); + + TRACE(stderr, "[regm_BinaryComparison]"); + + + switch (GETOP(pOpCode)) + { + case oBIT: + regm_GenerateForm3R(rAND, dwRDest, dwROperand1, dwROperand2); + regm_GenerateForm1ICc(rCMPI, dwRDest, 0, dwCcRegister); + break; + + default: + regm_GenerateForm1RCc(rCMP, dwROperand1, dwROperand2, dwCcRegister); + break; + } + + regm_GenerateForm2I(rMOVI, dwRDest, 0); + regm_GenerateForm4ICc(pEntry->chOpCode, 2, dwCcRegister); + regm_GenerateForm2I(rMOVI, dwRDest, 1); + + /* Reduce stack */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* Load from the address on the stack. Stack is unchanged */ + +static void regm_LoadImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRDest = dwROperand1; + + TRACE(stderr, "[regm_LoadImmediate]"); + + /* Use the immediate value as an index against the SPB/LSP */ + + regm_GenerateForm3R(pEntry->chOpCode, dwRDest, dwROperand1, + MKSPECIAL(pEntry->chSpecial)); +} + +/***********************************************************************/ +/* Generic load multiple logic */ + +static void regm_LoadMultiple(uint32_t dwRDest, uint32_t dwRSrc) +{ + TRACE(stderr, "[regm_LoadMultiple]"); + + if (g_bRegisterCountValid) + { + regm_GenerateForm3I(rLDM, dwRDest, dwRSrc, g_dwRegisterCount); + + /* Adjust the stack for the g_dwRegisterCount values added to the + * stack. + */ + + g_dwStackOffset += g_dwRegisterCount * sINT_SIZE; + g_bRegisterCountValid = 0; + } + else + { + fatal(ePOFFCONFUSION); + } +} + +/***********************************************************************/ +/* SPB/LSP relative source offset is on the stack. Stack increase determined + * by content of DC register. + */ + +static void regm_LoadMultipleImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRDest = dwRSrc; + + TRACE(stderr, "[regm_LoadMultipleImmediate]"); + + /* Adjust the src for the SPB/LSP value and generate the multiple load */ + + regm_GenerateForm3R(rADD, dwRSrc, dwRSrc, MKSPECIAL(pEntry->chSpecial)); + regm_LoadMultiple(dwRSrc, dwRDest); + + /* Stack will be increased by an amount determined by DC in + * regm_LoadMultiple. However, we need to also account for the + * immediate stack value that we consume here. + */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* Store value on stack to address on stack. Stack is reduced by two */ + +static void regm_StoreImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwROperand1 = MKREG(g_dwStackOffset - 2*sINT_SIZE); + + TRACE(stderr, "[regm_StoreImmediate]"); + + /* Use the immediate value as an index against the SPB/LSP */ + + regm_GenerateForm3R(pEntry->chOpCode, dwRSrc, dwROperand1, + MKSPECIAL(pEntry->chSpecial)); + + /* Reduce stack */ + + g_dwStackOffset -= 2*sINT_SIZE; +} + +/***********************************************************************/ +/* Generic store multiple logic */ + +static void regm_StoreMultiple(uint32_t dwRDest, uint32_t dwRSrc) +{ + TRACE(stderr, "[regm_StoreMultiple]"); + + if (g_bRegisterCountValid) + { + regm_GenerateForm3I(rSTM, dwRSrc, dwRDest, g_dwRegisterCount); + + /* Adjust the stack for the g_dwRegisterCount values added to the + * stack. + */ + + g_dwStackOffset -= g_dwRegisterCount * sINT_SIZE; + g_bRegisterCountValid = 0; + } + else + { + fatal(ePOFFCONFUSION); + } +} + +/***********************************************************************/ +/* Store multiple values on stack to address on stack. Stack is reduced + * by an amount determined by the content of DC. + */ + +static void regm_StoreMultipleImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRDest = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRSrc = MKREG(g_dwStackOffset - (g_dwRegisterCount + 1)*sINT_SIZE); + + TRACE(stderr, "[regm_StoreMultipleImmediate]"); + + /* Adjust the src for the SPB/LSP value and generate the multiple load */ + + regm_GenerateForm3R(rADD, dwRDest, dwRDest, MKSPECIAL(pEntry->chSpecial)); + regm_StoreMultiple(dwRSrc, dwRDest); + + /* Stack will be increased by an amount determined by DC in + * regm_StoreMultiple. However, we need to also account for the + * immediate stack value that we consume here. + */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* Duplicate the TOS. stack increases by one */ + +static void regm_Duplicate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRDest = MKREG(g_dwStackOffset); + + TRACE(stderr, "[regm_Duplicate]"); + + /* Generate the binary operation */ + + regm_GenerateForm2R(rMOV, dwRDest, dwROperand1); + + /* Increment the stack */ + + g_dwStackOffset += sINT_SIZE; +} + +/***********************************************************************/ +/* Put the immediate value at the top of the stack. Increment stack */ + +static void regm_PushImmediate(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRDest = g_dwStackOffset; + + TRACE(stderr, "[regm_PushImmediate]"); + + /* The value may be too large to represent with a MOVI, but we'll handle + * that later. + */ + + regm_GenerateForm2I(rMOVI, dwRDest, GETARG(pOpCode)); + + /* Increment the stack */ + + g_dwStackOffset += sINT_SIZE; +} + +/***********************************************************************/ +/* Push the special register onto the stack. Stack increments by one */ + +static void regm_PushSpecial(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRDest = g_dwStackOffset; + + TRACE(stderr, "[regm_PushSpecial]"); + + regm_GenerateForm2R(rMOV, dwRDest, MKSPECIAL(pEntry->chSpecial)); + + /* Increment the stack */ + + g_dwStackOffset += sINT_SIZE; +} + +/***********************************************************************/ +/* Pop the TOS into the special register. Stack decrements by one */ + +static void regm_PopSpecial(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); + + TRACE(stderr, "[regm_PopSpecial]"); + + regm_GenerateForm2R(rMOV, MKSPECIAL(pEntry->chSpecial), dwROperand1); + + /* Decrement the stack */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* Save the immediate value in the data count register */ + +static void regm_SetDataCount(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + /* We don't acutally use the DC register. It is an artifact just + * get here. We save the byte count as a even number of registers. + */ + + g_dwRegisterCount = (GETARG(pOpCode) + 3) >> 2; + g_bRegisterCountValid = 1; +} + +/***********************************************************************/ + +static void regm_Return(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + TRACE(stderr, "[regm_Return]"); + + /* This should have been processed by the prologue/epilogue logic */ + + fatal(ePOFFCONFUSION); +} + +/***********************************************************************/ +/* Load at offset from SPB/LSP. Stack increases by one */ + +static void regm_LoadOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRDest = g_dwStackOffset; + + TRACE(stderr, "[regm_LoadOffset]"); + + /* Use the immediate value as an index against the SPB/LSP */ + + regm_GenerateForm3I(pEntry->chOpCode, dwRDest, MKSPECIAL(pEntry->chSpecial), + GETARG(pOpCode) >> pEntry->chImmediate); + + /* Increment the stack */ + + g_dwStackOffset += sINT_SIZE; +} + +/***********************************************************************/ +/* Load multiple registgers at offset from SPB/LSP. Stack increase depends + * on value in DC (only) + */ + +static void regm_LoadMultipleOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRSrc = MKREG(g_dwStackOffset); + uint32_t dwRDest = dwRSrc; + + TRACE(stderr, "[regm_LoadMultipleOffset]"); + + regm_GenerateForm3R(rADD, dwRSrc, MKSPECIAL(pEntry->chSpecial), + GETARG(pOpCode)); + regm_LoadMultiple(dwRSrc, dwRDest); +} + +/***********************************************************************/ +/* Store at offset from SPB/LSP. Stack decreases by one */ + +static void regm_StoreOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); + + TRACE(stderr, "[regm_StoreOffset]"); + + /* Use the immediate value as an index against the SPB/LSP */ + + regm_GenerateForm3I(pEntry->chOpCode, dwRSrc, + MKSPECIAL(pEntry->chSpecial), + GETARG(pOpCode) >> pEntry->chImmediate); + + /* Decrement the stack */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* Store multiple at offset from SPB/LSP. Stack decreases an amount + * determined by the content of the DC regsiter. + */ + +static void regm_StoreMultipleOffset(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRSrc = MKREG(g_dwStackOffset - g_dwRegisterCount*sINT_SIZE); + uint32_t dwRDest; + + TRACE(stderr, "[regm_StoreMultipleOffset]"); + + regm_GenerateForm3R(rADD, dwRDest, MKSPECIAL(pEntry->chSpecial), + GETARG(pOpCode)); + regm_StoreMultiple(dwRSrc, dwRDest); +} + +/***********************************************************************/ +/* Load value using index on stack + argument + SPB/LSP. Stack is unchanged */ + +static void regm_LoadIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRDest = dwRIndex; + + TRACE(stderr, "[regm_LoadIndexed]"); + + /* Add the SPB/LSP to the index to make it relative to the stack, + * then use this with the immediate values to obtain the data. + */ + + regm_GenerateForm3R(rADD, dwRIndex, dwRIndex, + MKSPECIAL(pEntry->chSpecial)); + regm_GenerateForm3I(pEntry->chOpCode, dwRDest, dwRDest, + GETARG(pOpCode) >> pEntry->chImmediate); +} + +/***********************************************************************/ +/* Load multiple values using index on stack + argument + SPB/LSP. Stack + * will increase my an amount that depends on the contents of DC. + */ + +static void regm_LoadMultipleIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRSrc = dwRIndex; + uint32_t dwRDest = dwRIndex; + + TRACE(stderr, "[regm_LoadMultipleIndexed]"); + + /* Add the SPB/LSP to the index to make it relative to the stack, + * add the offset, then generate the multple load. + */ + + regm_GenerateForm3R(rADD, dwRSrc, dwRIndex, + MKSPECIAL(pEntry->chSpecial)); + regm_GenerateForm3I(rADDI, dwRSrc, dwRSrc, GETARG(pOpCode)); + regm_LoadMultiple(dwRSrc, dwRDest); + + /* Stack will be increased by an amount determined by DC in + * regm_LoadMultiple. However, we need to also account for the + * index stack value that we consume here. + */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* Store value at TOS to index + offset + SPB/LSP. Stack decreases by two */ + +static void regm_StoreIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRSrc = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRIndex = MKREG(g_dwStackOffset - 2*sINT_SIZE); + + TRACE(stderr, "[regm_StoreIndexed]"); + + /* Add the LSP to the index to make it relative to the stack, + * then use this with the immediate values to obtain the data. + */ + + regm_GenerateForm3R(rADD, dwRIndex, dwRIndex, + MKSPECIAL(pEntry->chSpecial)); + regm_GenerateForm3I(pEntry->chOpCode, dwRSrc, dwRIndex, + GETARG(pOpCode) >> pEntry->chImmediate); + + /* Decrement the stack */ + + g_dwStackOffset -= 2*sINT_SIZE; +} + +/***********************************************************************/ +/* Store values at TOS to index + offset + SPB/LSP. Stack decreases by + * amount determined by the content of the DC register. + */ + +static void regm_StoreMultipleIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRSrc = MKREG(g_dwStackOffset - (g_dwRegisterCount + 1)*sINT_SIZE); + uint32_t dwRDest; + + TRACE(stderr, "[regm_StoreMultipleIndexed]"); + + /* Adjust the src for the SPB/LSP value and generate the multiple load */ + + regm_GenerateForm3R(rADD, dwRDest, dwRIndex, + MKSPECIAL(pEntry->chSpecial)); + regm_GenerateForm3I(rADDI, dwRDest, dwRDest, GETARG(pOpCode)); + regm_StoreMultiple(dwRSrc, dwRDest); + + /* Stack will be increased by an amount determined by DC in + * regm_StoreMultiple. However, we need to also account for the + * immediate stack value that we consume here. + */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* These pcodes are all conditional branch operations. The pcode form + * takes one input (that is compared with zero) and branches based + * the result. The stack is decremented by one. + */ + +static void regm_ConditionalBranchVsZero(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwUnaryRegister = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwCcRegister = MKCCREG(g_dwStackOffset); + + TRACE(stderr, "[regm_ConditionalBranchVsZero]"); + + + regm_GenerateForm1ICc(rCMPI, dwUnaryRegister, 0, dwCcRegister); + regm_GenerateForm4ICc(pEntry->chOpCode, GETARG(pOpCode), dwCcRegister); + + /* Decrement the stack */ + + g_dwStackOffset -= sINT_SIZE; +} + +/***********************************************************************/ +/* These pcodes are all conditional branch operations. The pcode form + * takes two inputs that are compared. The pcode branches on the result + * of the comparison. The stack is reduced by two. + */ + +static void regm_ConditionalBranchBinary(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwROperand1 = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwROperand2 = MKREG(g_dwStackOffset - 2*sINT_SIZE); + uint32_t dwCcRegister = MKCCREG(g_dwStackOffset); + + TRACE(stderr, "[regm_BinaryComparison]"); + + /* Generate the compare and branch */ + + regm_GenerateForm1RCc(rCMP, dwROperand1, dwROperand2, dwCcRegister); + regm_GenerateForm4ICc(pEntry->chOpCode, GETARG(pOpCode), dwCcRegister); + + /* Reduce stack */ + + g_dwStackOffset -= 2*sINT_SIZE; +} + +/***********************************************************************/ +/* Branch unconditionally. The stack is not changed */ + +static void regm_UnconditionalBranch(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + TRACE(stderr, "[regm_UnconditionalBranch]"); + regm_GenerateForm4I(rB, GETARG(pOpCode)); +} + +/***********************************************************************/ +/* Add constant value to special register. Stack does not change */ + +static void regm_IncrementSpecial(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + int32_t dwIncrement = (int32_t)(GETOP(pOpCode)); + uint32_t dwRSpecial = MKSPECIAL(pEntry->chSpecial); + TRACE(stderr, "[regm_IncrementSpecial]"); + + /* The value may be too large to represent with a MOVI, but we'll handle + * that later. + */ + + if (dwIncrement < 0) + { + regm_GenerateForm3I(rSUBI, dwRSpecial, dwRSpecial, -dwIncrement); + } + else if (dwIncrement > 0) + { + regm_GenerateForm3I(rADDI, dwRSpecial, dwRSpecial, dwIncrement); + } + + if (pEntry->chSpecial == SP) + { + g_dwStackOffset += dwIncrement; + } +} + +/***********************************************************************/ +/* Load address at offset from special register. Stack increases by one */ + +static void regm_LoadAddress(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRDest = g_dwStackOffset; + + TRACE(stderr, "[regm_LoadAddress]"); + + /* Use the immediate value as an index against the SPB/LSP */ + + regm_GenerateForm3I(rADD, dwRDest, MKSPECIAL(pEntry->chSpecial), + GETARG(pOpCode)); + + /* Increment the stack */ + + g_dwStackOffset += sINT_SIZE; +} + +/***********************************************************************/ +/* Load address at indexed offset from special register. Stack is unchanged */ + +static void regm_LoadAddressIndexed(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + uint32_t dwRIndex = MKREG(g_dwStackOffset - 1*sINT_SIZE); + uint32_t dwRDest = dwRIndex; + + TRACE(stderr, "[regm_LoadAddressIndexed]"); + + /* Add the LSP or SPB to the index to make it relative to the stack, + * then use this with the immediate values to obtain the data. + */ + + regm_GenerateForm3R(rADD, dwRIndex, dwRIndex, + MKSPECIAL(pEntry->chSpecial)); + regm_GenerateForm3I(rADD, dwRDest, dwRIndex, GETARG(pOpCode)); +} + +/***********************************************************************/ + +static void regm_SetupOutArgs(uint32_t nParms, const uint32_t *pwArgSize) +{ + int nArgRegs; + int32_t dwOffset; + int i; + + for (i = 0, nArgRegs = 0; i < nParms; i++) + { + nArgRegs += (pwArgSize[i] + 3) >> 2; + } + + /* Emit move instructions to handle each */ + + dwOffset = g_dwStackOffset - sINT_SIZE; + for (i = 0; i < nArgRegs; i++) + { + uint32_t dwDest = MKOUTARG(i); + uint32_t dwSrc = MKREG(dwOffset); + + regm_GenerateForm2R(rMOV, dwDest, dwSrc); + dwOffset -= sINT_SIZE; + } +} + +/***********************************************************************/ + +static void regm_MapInRet(uint32_t wRetSize) +{ + int nRetRegs; + int32_t dwOffset; + int i; + + /* Get the number of registers that are returned */ + + nRetRegs += (wRetSize + 3) >> 2; + + /* Emit move instructions to handle each */ +#warning "This offset is not correct" + dwOffset = g_dwStackOffset - sINT_SIZE; + for (i = 0; i < nRetRegs; i++) + { + uint32_t dwSrc = MKINRET(i); + uint32_t dwDest = MKREG(dwOffset); + + regm_GenerateForm2R(rMOV, dwDest, dwSrc); + dwOffset -= sINT_SIZE; + } +} + +/***********************************************************************/ + +static void regm_PCal(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + poffLibDebugFuncInfo_t *pFuncInfo = pNode->pFuncInfo; + + TRACE(stderr, "[regm_PCal]"); + + if (!pFuncInfo) + { + fatal(ePOFFCONFUSION); + } + + /* Map the "output" parameter stack to a set of "output" argument + * registers. + */ + + regm_SetupOutArgs(pFuncInfo->nparms, pFuncInfo->argsize); + + regm_GenerateForm3I(rADDI, MKSPECIAL(SP), MKSPECIAL(SP), 3*sINT_SIZE); + regm_GenerateForm3I(rST, MKSPECIAL(LSP), MKSPECIAL(SP), -3); + regm_GenerateForm3I(rST, MKSPECIAL(BRG), MKSPECIAL(SP), -2); + regm_GenerateForm4I(rBL, GETARG(pOpCode)); + +#warning "This is in the wrong place" + regm_MapInRet(pFuncInfo->retsize); + + /* Increment the stack */ + + g_dwStackOffset += 3*sINT_SIZE; +} + +/***********************************************************************/ + +static void regm_SysIo(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + const struct regm_builtin_s *pBuiltIn; + uint32_t xop; + + TRACE(stderr, "[regm_SysIo]"); + + /* Get the function information for this sysio xop */ + + xop = GETARG(pOpCode); + if (xop >= MAX_XOP) + { + fatal(ePOFFCONFUSION); + } + + pBuiltIn = &g_rgSysIoBuiltIns[xop]; + + /* Map the "output" parameter stack to a set of "output" argument + * registers. + */ + + regm_SetupOutArgs(pBuiltIn->nParms, pBuiltIn->wArgSize); + + /* Generate a call to the runtime library */ + +#warning "Not implemented" + + /* Handled returned values */ + + regm_MapInRet(pBuiltIn->wRetSize); +} + +/***********************************************************************/ + +static void regm_LibCall(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + const struct regm_builtin_s *pBuiltIn; + uint32_t lbop; + + TRACE(stderr, "[regm_LibCall]"); + + /* Get the function information for this library op */ + + lbop = GETARG(pOpCode); + if (lbop >= MAX_LBOP) + { + fatal(ePOFFCONFUSION); + } + + pBuiltIn = &g_rgLibCallBuiltIns[lbop]; + + /* Map the "output" parameter stack to a set of "output" argument + * registers. + */ + + regm_SetupOutArgs(pBuiltIn->nParms, pBuiltIn->wArgSize); + + /* Generate a call to the runtime library */ + +#warning "Not implemented" + + /* Handled returned values */ + + regm_MapInRet(pBuiltIn->wRetSize); +} + +/***********************************************************************/ + +static void regm_Float(const struct regm_opmap_s *pEntry, OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + static const struct regm_builtin_s *pFopBuiltIns; + const struct regm_builtin_s *pBuiltIn; + uint32_t foptab; + uint32_t fop; + + TRACE(stderr, "[regm_FLoat]"); + + /* Select the correct table for the builtin */ + + foptab = (GETARG(pOpCode) & ~fpMASK) >> fpSHIFT; + pFopBuiltIns = g_prgFopBuiltIns[foptab]; + + /* Select the correct function from the table for this floating + * point operation. + */ + + fop = GETARG(pOpCode) & fpMASK; + if (fop >= MAX_FOP) + { + fatal(ePOFFCONFUSION); + } + pBuiltIn = &pFopBuiltIns[fop]; + + /* Map the "output" parameter stack to a set of "output" argument + * registers. + */ + + regm_SetupOutArgs(pBuiltIn->nParms, pBuiltIn->wArgSize); + + /* Generate a call to the runtime library */ + +#warning "Not implemented" + + /* Handled returned values */ + + regm_MapInRet(pBuiltIn->wRetSize); +} + +/***********************************************************************/ + +static void regm_IllegalPCode(const struct regm_opmap_s *pEntry, + OPTYPE *pOpCode, + struct procdata_s *pNode) +{ + TRACE(stderr, "[regm_IllegalPCode]"); + fatal(eILLEGALOPCODE); +} + +/***********************************************************************/ + +static void regm_GenerateRegm(struct procdata_s *pNode, void *pvArg) +{ + int32_t dwFrameSize = 0; + int i, j; + + TRACE(stderr, "[regm_GenerateRegm]"); + + /* Analyze the proc/func prologue */ + + i = 0; j = pNode->nPCodes; + if (GETOP(&pNode->pPCode[0]) == oINDS) + { + dwFrameSize = GETARG(&pNode->pPCode[0]); + i++; j--; + } + regm_GeneratePrologue(dwFrameSize); + + /* Set the initial stack offset. Parameters will look like + * negative offsets; local stack will look positive. + */ + + g_dwStackOffset = dwFrameSize; + + /* Generate regm code for each p-code */ + + for (; i < j; i++) + { + const struct regm_opmap_s *rgOpMap; + uint8_t chOpCode = GETOP(&pNode->pPCode[i]); + + /* Select the right decode table */ + + if ((chOpCode & o32) != 0) + { + rgOpMap = vrgOpMap2; + chOpCode &= ~o32; + } + else + { + rgOpMap = vrgOpMap1; + } + + /* Make sure that the table index is within range */ + + if (chOpCode > 63) + { + fatal(eBADSHORTINT); + } + + /* Perform the opcode mapping */ + + rgOpMap->pMapper(rgOpMap, &pNode->pPCode[i], pNode); + } + + /* If a frame was obtained at the beginning, make sure that + * there is matching frame release logic at the end. + */ + + if (dwFrameSize > 0) + { + if ((GETOP(&pNode->pPCode[i]) != oINDS) || + (dwFrameSize != -(int32_t)GETARG(&pNode->pPCode[i]))) + { + fatal(ePOFFCONFUSION); + } + i++; + } + + /* Analyze the proc/func epilogue */ + + if ((GETOP(&pNode->pPCode[i]) != oRET) && + (GETOP(&pNode->pPCode[i]) != oEND)) + { + fatal(ePOFFCONFUSION); + } + regm_GenerateEpilogue(dwFrameSize); +} + +/***********************************************************************/ + +static int regm_Pass2Node(struct procdata_s *pNode, void *pvArg) +{ + TRACE(stderr, "[regm_Pass2Node]"); + + /* Generate code for each child of this proc/func block */ + + if (pNode->child) + { + (void)regm_ForEachChild(pNode->child, regm_Pass2Node, pvArg); + } + + /* Generate code for this node */ + + regm_GenerateRegm(pNode, pvArg); + + /* Does this node have a peer at the same level? If so, then + * do the same for its peer. + */ + + if (pNode->peer) + { + (void)regm_Pass2Node(pNode->peer, pvArg); + } + + return 0; +} + +/********************************************************************** + * Public Functions + **********************************************************************/ + +/***********************************************************************/ +/* Pass 2: Convert the buffered pcode to the basic register model with + * an indefinite number of registers (arguments, general, and special + * registers) and with 32-bit immediate size. + */ + +void regm_Pass2(poffHandle_t hPoff) +{ + TRACE(stderr, "[regm_Pass2]"); + + /* Initiate traversal at the root node */ + + (void)regm_Pass2Node(regm_GetRootNode(), NULL); +} + +/***********************************************************************/ + diff --git a/misc/pascal/insn32/regm/regm_pass2.h b/misc/pascal/insn32/regm/regm_pass2.h index ab580d42d..8d3ba91db 100644 --- a/misc/pascal/insn32/regm/regm_pass2.h +++ b/misc/pascal/insn32/regm/regm_pass2.h @@ -1,66 +1,68 @@ -/*************************************************************************** - * regm_pass2.h - * External Declarations associated with regm_pass2.c - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ***************************************************************************/ - -#ifndef __REGM_PASS2_H -#define __REGM_PASS2_H - -/*************************************************************************** - * Included Files - ***************************************************************************/ - -/*************************************************************************** - * Definitions - ***************************************************************************/ - -/*************************************************************************** - * Public Types - ***************************************************************************/ - -/*************************************************************************** - * Public Variables - ***************************************************************************/ - -extern uint32 g_dwStackOffset; -extern uint32 g_dwRegisterCount; -extern int g_bRegisterCountValid; - -/*************************************************************************** - * Public Function Prototypes - ***************************************************************************/ - -extern void regm_Pass2(poffHandle_t hPoff); - -#endif /* __REGM_PASS2_H */ +/*************************************************************************** + * regm_pass2.h + * External Declarations associated with regm_pass2.c + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ***************************************************************************/ + +#ifndef __REGM_PASS2_H +#define __REGM_PASS2_H + +/*************************************************************************** + * Included Files + ***************************************************************************/ + +#include + +/*************************************************************************** + * Definitions + ***************************************************************************/ + +/*************************************************************************** + * Public Types + ***************************************************************************/ + +/*************************************************************************** + * Public Variables + ***************************************************************************/ + +extern uint32_t g_dwStackOffset; +extern uint32_t g_dwRegisterCount; +extern int g_bRegisterCountValid; + +/*************************************************************************** + * Public Function Prototypes + ***************************************************************************/ + +extern void regm_Pass2(poffHandle_t hPoff); + +#endif /* __REGM_PASS2_H */ diff --git a/misc/pascal/insn32/regm/regm_registers2.c b/misc/pascal/insn32/regm/regm_registers2.c index 2973dc7c3..25aaddfaf 100644 --- a/misc/pascal/insn32/regm/regm_registers2.c +++ b/misc/pascal/insn32/regm/regm_registers2.c @@ -1,541 +1,542 @@ -/********************************************************************** - * regm_registers.c - * Pass 2 register management functions - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include -#include -#include - -#include "keywords.h" -#include "pofflib.h" -#include "pedefs.h" -#include "perr.h" - -#include "rinsn32.h" - -#include "regm.h" -#include "regm_pass2.h" -#include "regm_registers2.h" - -/********************************************************************** - * Definitions - **********************************************************************/ - -#define INITIAL_RCODE2_ALLOC 150 -#define RCODE2_REALLOC 50 - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -/********************************************************************** - * Public Variables - **********************************************************************/ - -struct regm_rcode2_s *g_pRCode2 = NULL; -uint32 g_nRCode2 = 0; - -/********************************************************************** - * Private Variables - **********************************************************************/ - -static uint32 g_nRCode2Alloc = 0; - -static const char * const g_prgReg2Names[NREGISTER_TYPES] = - { "Z", "X", "CC", "A", "R", "V", "V", "S" }; - -static const char * const g_prgSpecialReg2Names[NSPECIAL_REGISTERS2] = - { "SPB", "SP", "BRG", "LSP", "CSB", "CSP", "PC", "DC", "LR", "CC"}; - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/***********************************************************************/ - -static void regm_CheckRCode2Alloc(void) -{ - /* If the RCode buffer has never been allocated, allocate it now. */ - - if (!g_pRCode2) - { - /* Allocate an inital buffer to hold the instructions */ - - g_pRCode2 = (struct regm_rcode2_s*) - malloc(INITIAL_RCODE2_ALLOC*sizeof(struct regm_rcode2_s)); - if (!g_pRCode2) - { - fatal(eNOMEMORY); - } - - g_nRCode2Alloc = INITIAL_RCODE2_ALLOC; - } - - /* The buffer has already been allocated, is there space for one - * more RCode? - */ - - else if (g_nRCode2 >= g_nRCode2Alloc) - { - /* If not, then reallocate the array */ - - g_pRCode2 = (struct regm_rcode2_s*) - realloc(g_pRCode2, g_nRCode2Alloc*sizeof(struct regm_rcode2_s)); - if (!g_pRCode2) - { - fatal(eNOMEMORY); - } - - g_nRCode2Alloc += RCODE2_REALLOC; - } -} - -/***********************************************************************/ - -struct regm_rcode2_s *regm_AllocateRCode2(void) -{ - struct regm_rcode2_s *pRetSlot; - - /* Make sure we have memory allocated in the array for another - * RCode. - */ - - regm_CheckRCode2Alloc(); - - /* Return the reference to the next RCode slot */ - - pRetSlot = &g_pRCode2[g_nRCode2]; - g_nRCode2++; - return pRetSlot; -} - -static void regm_PrintSpecialReg2(FILE *pStream, uint32 dwRegister) -{ - int wRegNo = regm_GetRegNo(dwRegister); - if (wRegNo >= NSPECIAL_REGISTERS2) - fputc('?', pStream); - else - fputs(g_prgSpecialRegNames[wRegNo], pStream); -} - -static void regm_PrintReg2(FILE *pStream, uint32 dwRegister) -{ - int wKind = regm_GetKind(dwRegister); - int wRegNo = regm_GetRegNo(dwRegister) - if (wKind >= REGISTERS_TYPES) - fprintf(pStream, "?%d", wRegNo); - else if (wKind == SPECIAL_REG) - regm_PrintSpecialReg(fg, dwRegister); - else - fprintf(pStream, "%s%d", g_prgRegNames[wKind], wRegNo); -} - -static void regm_PrintDebugReg(const char *string, uint32 dwRegister) -{ - if (vRegmDebug) - { - fputs(string, DEBUG_FILE); - regm_PrintReg2(DEBUG_FILE, dwRegister); - fputc('\n', DEBUG_FILE); - } -} - -/***********************************************************************/ - -static void regm_MarkRegisterUsed(struct regm_rcode2_s *pReg, - uint32 dwRegister) -{ - regm_PrintDebugReg("Register used: ", dwRegister); - - switch (regm_GetKind(dwRegister)) - { - case SPECIAL_REG : /* Special "global" registers */ - break; /* (ignored) */ - - case CC_REG : /* Condition code register instance (fake) */ - break; - - case INARG_REG : /* Volatile register for input arguments */ - /* and output values from/to callee */ - break; - - case OUTARG_REG : /* Volatile register for output arguments */ - /* and input values to/from called */ - /* function (fake) */ - break; - - case SCRATCH_REG : /* Volatile register for general usage */ - break; - - case VOLATILE_REG : /* Volatile registers in general */ - case STATIC_REG : /* Static register */ - default: - fatal(ePOFFCONFUSION); - break; - } -#warning "Not Implemeted" -} - -/***********************************************************************/ - -static void regm_MarkRegisterModified(struct regm_rcode2_s *pReg, - uint32 dwRegister) -{ - regm_PrintDebugReg("Register modified: ", dwRegister); - - switch (regm_GetKind(dwRegister)) - { - case SPECIAL_REG : /* Special "global" registers */ - break; /* (ignored) */ - - case CC_REG : /* Condition code register instance (fake) */ - break; - - case INARG_REG : /* Volatile register for input arguments */ - /* and output values from/to callee */ - break; - - case OUTARG_REG : /* Volatile register for output arguments */ - /* and input values to/from called */ - /* function (fake) */ - break; - - case SCRATCH_REG : /* Volatile register for general usage */ - break; - - case VOLATILE_REG : /* Volatile registers in general */ - case STATIC_REG : /* Static register */ - default: - fatal(ePOFFCONFUSION); - break; - } -#warning "Not Implemeted" -} - -/********************************************************************** - * Public Functions - **********************************************************************/ - -/***********************************************************************/ -/* Generate function prologue: Save return address, create stack frame - * for local variables, and save static registers that till be used. - */ - -void regm_GeneratePrologue(uint32 dwFrameSize) -{ -#warning "Not implemented" -} - -/***********************************************************************/ -/* Restore static registers, release stack frame and return */ - -void regm_GenerateEpilogue(uint32 dwFrameSize) -{ -#warning "Not implemented" -} - -/***********************************************************************/ -/* Register-to-register comparisons (e.g., cmp r1, r2) - * - * FORM 1R: , - */ - -void regm_GenerateForm1RCc(ubyte chOp, uint32 dwROperand1, - uint32 dwROperand2, uint32 dwRCc) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_1RCc; - pReg->chOp = chOp; - pReg->u.f1rcc.dwROperand1 = dwROperand1; - pReg->u.f1rcc.dwROperand2 = dwROperand2; - pReg->u.f1rcc.dwRCc = dwRCc; - - regm_MarkRegisterUsed(pReg, dwROperand1); - regm_MarkRegisterUsed(pReg, dwROperand2); - regm_MarkRegisterModified(pReg, dwRCc); -} - -/***********************************************************************/ -/* Register-to-immediate comparisons (e.g., cmpi r1, 1) - * - * FORM 1I: , - */ - -void regm_GenerateForm1ICc(ubyte chOp, uint32 dwROperand1, - uint32 dwImmediate, uint32 dwRCc) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_1ICc; - pReg->chOp = chOp; - pReg->u.f1icc.dwROperand1 = dwROperand1; - pReg->u.f1icc.dwImmediate = dwImmediate; - pReg->u.f1icc.dwRCc = dwRCc; - - regm_MarkRegisterUsed(pReg, dwROperand1); - regm_MarkRegisterModified(pReg, dwRCc); -} - -/***********************************************************************/ -/* Register-to-register mov instructions (e.g, mov r1, r2) - * - * FORM 2R: , - */ - -void regm_GenerateForm2R(ubyte chOp, uint32 dwRDest, - uint32 dwROperand2) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_2R; - pReg->chOp = chOp; - pReg->u.f2r.dwRDest = dwRDest; - pReg->u.f2r.dwROperand2 = dwROperand2; - - regm_MarkRegisterModified(pReg, dwRDest); - regm_MarkRegisterUsed(pReg, dwROperand2); -} - -/***********************************************************************/ -/* Immediate-to-register mov instructions (e.g, movi r1, 1) - * -/* FORM 2I: , -*/ - -void regm_GenerateForm2I(ubyte chOp, uint32 dwRDest, - uint32 dwImmediate) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_2I; - pReg->chOp = chOp; - pReg->u.f2i.dwRDest = dwRDest; - pReg->u.f2i.dwImmediate = dwImmediate; - - regm_MarkRegisterModified(pReg, dwRDest); -} - -/***********************************************************************/ -/* Binary operations (e.g., add r0, r1, r2) - * Load operations (e.g., ld r0, [r1, r2]) - * Store operations (e.g., st r0, [r1, r2]) - * - * FORM 3R: , , - * , , - */ - -void regm_GenerateForm3R(ubyte chOp, uint32 dwRSrcDest, - uint32 dwROperand1, uint32 dwROperand2) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_3R; - pReg->chOp = chOp; - pReg->u.f3r.dwRSrcDest = dwRSrcDest; - pReg->u.f3r.dwROperand1 = dwROperand1; - pReg->u.f3r.dwROperand2 = dwROperand2; - - switch (chOp) - { - /* FORM 3: Arithmetic and logical operations */ - /* FORM 3: Loads */ - - case rADD : - case rSUB : - case rRSB : - case rMUL : - case rDIV : - case rMOD : - case rSLL : - case rSRL : - case rSRA : - case rOR : - case rAND : - case rXOR : - case rANDN : - case rLD : - case rLDH : - case rLDB : - regm_MarkRegisterModified(pReg, dwRSrcDest); - break; - - /* FORM 3: Loads multiple */ - case rLDM : - { - uint32 dwRDest = dwRSrcDest; - int i; - for (i = 0; i < g_dwRegisterCount; i++) - { - regm_MarkRegisterModified(pReg, dwRDest); - dwRDest++; - } - } - break; - - /* FORM 3: Stores */ - case rST : - case rSTH : - case rSTB : - regm_MarkRegisterUsed(pReg, dwRSrcDest); - break; - - /* FORM 3: Store multipole */ - case rSTM : - { - uint32 dwRSrc = dwRSrcDest; - int i; - for (i = 0; i < g_dwRegisterCount; i++) - { - regm_MarkRegisterUsed(pReg, dwRSrc); - dwRSrc++; - } - } - break; - - default: - fatal(ePOFFCONFUSION); - } - - regm_MarkRegisterUsed(pReg, dwROperand1); - regm_MarkRegisterUsed(pReg, dwROperand2); -} - -/***********************************************************************/ -/* Binary operations (e.g., addi r0, r1, 1) - * Load operations (e.g., ldi r0, [r1, 4]) - * Store operations (e.g., sti r0, [r1, 4]) - * - * FORM 3I: , , - * , , - */ - -void regm_GenerateForm3I(ubyte chOp, uint32 dwRSrcDest, - uint32 dwROperand1, uint32 dwImmediate) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_3I; - pReg->chOp = chOp; - pReg->u.f3i.dwRSrcDest = dwRSrcDest; - pReg->u.f3i.dwROperand1 = dwROperand1; - pReg->u.f3i.dwImmediate = dwImmediate; - - switch (chOp) - { - /* FORM 3: Arithmetic and logical operations */ - /* FORM 3: Loads */ - - case rADDI : - case rSUBI : - case rRSBI : - case rMULI : - case rDIVI : - case rMODI : - case rSLLI : - case rSRLI : - case rSRAI : - case rORI : - case rANDI : - case rXORI : - case rANDNI : - case rLDI : - case rLDIH : - case rLDIB : - regm_MarkRegisterModified(pReg, dwRSrcDest); - break; - - /* FORM 3: Stores */ - case rSTI : - case rSTIH : - case rSTIB : - regm_MarkRegisterUsed(pReg, dwRSrcDest); - break; - - default: - fatal(ePOFFCONFUSION); - } - - regm_MarkRegisterUsed(pReg, dwROperand1); -} - -/***********************************************************************/ -/* Unconditional branch operations (b offset, bl offset) - * - * FORM 4I: - */ - -void regm_GenerateForm4I(ubyte chOp, uint32 dwOffset) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_4I; - pReg->chOp = chOp; - pReg->u.f4i.dwOffset = dwOffset; -} - -/***********************************************************************/ -/* Conditional branch operations (e.g., beq offset) - * - * FORM 4I: - */ - -void regm_GenerateForm4ICc(ubyte chOp, uint32 dwOffset, - uint32 dwRCc) -{ - struct regm_rcode2_s *pReg = regm_AllocateRCode2(); - pReg->eForm = eFORM_4ICc; - pReg->chOp = chOp; - pReg->u.f4icc.dwOffset = dwOffset; - pReg->u.f4icc.dwRCc = dwRCc; - - regm_MarkRegisterUsed(pReg, dwRCc); -} - -/***********************************************************************/ - -int regm_ForEachRCode2(regm_rcode2_node_t pNode, void *arg) -{ - int ret; - int i; - for (i = 0; i < g_nRCode2; i++) - { - ret = pNode(&g_pRCode2[i], arg); - if (ret != 0) - { - return ret; - } - } - return 0; -} - -/***********************************************************************/ +/********************************************************************** + * regm_registers.c + * Pass 2 register management functions + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include +#include +#include + +#include "keywords.h" +#include "pofflib.h" +#include "pedefs.h" +#include "perr.h" + +#include "rinsn32.h" + +#include "regm.h" +#include "regm_pass2.h" +#include "regm_registers2.h" + +/********************************************************************** + * Definitions + **********************************************************************/ + +#define INITIAL_RCODE2_ALLOC 150 +#define RCODE2_REALLOC 50 + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +/********************************************************************** + * Public Variables + **********************************************************************/ + +struct regm_rcode2_s *g_pRCode2 = NULL; +uint32_t g_nRCode2 = 0; + +/********************************************************************** + * Private Variables + **********************************************************************/ + +static uint32_t g_nRCode2Alloc = 0; + +static const char * const g_prgReg2Names[NREGISTER_TYPES] = + { "Z", "X", "CC", "A", "R", "V", "V", "S" }; + +static const char * const g_prgSpecialReg2Names[NSPECIAL_REGISTERS2] = + { "SPB", "SP", "BRG", "LSP", "CSB", "CSP", "PC", "DC", "LR", "CC"}; + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/***********************************************************************/ + +static void regm_CheckRCode2Alloc(void) +{ + /* If the RCode buffer has never been allocated, allocate it now. */ + + if (!g_pRCode2) + { + /* Allocate an inital buffer to hold the instructions */ + + g_pRCode2 = (struct regm_rcode2_s*) + malloc(INITIAL_RCODE2_ALLOC*sizeof(struct regm_rcode2_s)); + if (!g_pRCode2) + { + fatal(eNOMEMORY); + } + + g_nRCode2Alloc = INITIAL_RCODE2_ALLOC; + } + + /* The buffer has already been allocated, is there space for one + * more RCode? + */ + + else if (g_nRCode2 >= g_nRCode2Alloc) + { + /* If not, then reallocate the array */ + + g_pRCode2 = (struct regm_rcode2_s*) + realloc(g_pRCode2, g_nRCode2Alloc*sizeof(struct regm_rcode2_s)); + if (!g_pRCode2) + { + fatal(eNOMEMORY); + } + + g_nRCode2Alloc += RCODE2_REALLOC; + } +} + +/***********************************************************************/ + +struct regm_rcode2_s *regm_AllocateRCode2(void) +{ + struct regm_rcode2_s *pRetSlot; + + /* Make sure we have memory allocated in the array for another + * RCode. + */ + + regm_CheckRCode2Alloc(); + + /* Return the reference to the next RCode slot */ + + pRetSlot = &g_pRCode2[g_nRCode2]; + g_nRCode2++; + return pRetSlot; +} + +static void regm_PrintSpecialReg2(FILE *pStream, uint32_t dwRegister) +{ + int wRegNo = regm_GetRegNo(dwRegister); + if (wRegNo >= NSPECIAL_REGISTERS2) + fputc('?', pStream); + else + fputs(g_prgSpecialRegNames[wRegNo], pStream); +} + +static void regm_PrintReg2(FILE *pStream, uint32_t dwRegister) +{ + int wKind = regm_GetKind(dwRegister); + int wRegNo = regm_GetRegNo(dwRegister) + if (wKind >= REGISTERS_TYPES) + fprintf(pStream, "?%d", wRegNo); + else if (wKind == SPECIAL_REG) + regm_PrintSpecialReg(fg, dwRegister); + else + fprintf(pStream, "%s%d", g_prgRegNames[wKind], wRegNo); +} + +static void regm_PrintDebugReg(const char *string, uint32_t dwRegister) +{ + if (vRegmDebug) + { + fputs(string, DEBUG_FILE); + regm_PrintReg2(DEBUG_FILE, dwRegister); + fputc('\n', DEBUG_FILE); + } +} + +/***********************************************************************/ + +static void regm_MarkRegisterUsed(struct regm_rcode2_s *pReg, + uint32_t dwRegister) +{ + regm_PrintDebugReg("Register used: ", dwRegister); + + switch (regm_GetKind(dwRegister)) + { + case SPECIAL_REG : /* Special "global" registers */ + break; /* (ignored) */ + + case CC_REG : /* Condition code register instance (fake) */ + break; + + case INARG_REG : /* Volatile register for input arguments */ + /* and output values from/to callee */ + break; + + case OUTARG_REG : /* Volatile register for output arguments */ + /* and input values to/from called */ + /* function (fake) */ + break; + + case SCRATCH_REG : /* Volatile register for general usage */ + break; + + case VOLATILE_REG : /* Volatile registers in general */ + case STATIC_REG : /* Static register */ + default: + fatal(ePOFFCONFUSION); + break; + } +#warning "Not Implemeted" +} + +/***********************************************************************/ + +static void regm_MarkRegisterModified(struct regm_rcode2_s *pReg, + uint32_t dwRegister) +{ + regm_PrintDebugReg("Register modified: ", dwRegister); + + switch (regm_GetKind(dwRegister)) + { + case SPECIAL_REG : /* Special "global" registers */ + break; /* (ignored) */ + + case CC_REG : /* Condition code register instance (fake) */ + break; + + case INARG_REG : /* Volatile register for input arguments */ + /* and output values from/to callee */ + break; + + case OUTARG_REG : /* Volatile register for output arguments */ + /* and input values to/from called */ + /* function (fake) */ + break; + + case SCRATCH_REG : /* Volatile register for general usage */ + break; + + case VOLATILE_REG : /* Volatile registers in general */ + case STATIC_REG : /* Static register */ + default: + fatal(ePOFFCONFUSION); + break; + } +#warning "Not Implemeted" +} + +/********************************************************************** + * Public Functions + **********************************************************************/ + +/***********************************************************************/ +/* Generate function prologue: Save return address, create stack frame + * for local variables, and save static registers that till be used. + */ + +void regm_GeneratePrologue(uint32_t dwFrameSize) +{ +#warning "Not implemented" +} + +/***********************************************************************/ +/* Restore static registers, release stack frame and return */ + +void regm_GenerateEpilogue(uint32_t dwFrameSize) +{ +#warning "Not implemented" +} + +/***********************************************************************/ +/* Register-to-register comparisons (e.g., cmp r1, r2) + * + * FORM 1R: , + */ + +void regm_GenerateForm1RCc(uint8_t chOp, uint32_t dwROperand1, + uint32_t dwROperand2, uint32_t dwRCc) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_1RCc; + pReg->chOp = chOp; + pReg->u.f1rcc.dwROperand1 = dwROperand1; + pReg->u.f1rcc.dwROperand2 = dwROperand2; + pReg->u.f1rcc.dwRCc = dwRCc; + + regm_MarkRegisterUsed(pReg, dwROperand1); + regm_MarkRegisterUsed(pReg, dwROperand2); + regm_MarkRegisterModified(pReg, dwRCc); +} + +/***********************************************************************/ +/* Register-to-immediate comparisons (e.g., cmpi r1, 1) + * + * FORM 1I: , + */ + +void regm_GenerateForm1ICc(uint8_t chOp, uint32_t dwROperand1, + uint32_t dwImmediate, uint32_t dwRCc) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_1ICc; + pReg->chOp = chOp; + pReg->u.f1icc.dwROperand1 = dwROperand1; + pReg->u.f1icc.dwImmediate = dwImmediate; + pReg->u.f1icc.dwRCc = dwRCc; + + regm_MarkRegisterUsed(pReg, dwROperand1); + regm_MarkRegisterModified(pReg, dwRCc); +} + +/***********************************************************************/ +/* Register-to-register mov instructions (e.g, mov r1, r2) + * + * FORM 2R: , + */ + +void regm_GenerateForm2R(uint8_t chOp, uint32_t dwRDest, + uint32_t dwROperand2) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_2R; + pReg->chOp = chOp; + pReg->u.f2r.dwRDest = dwRDest; + pReg->u.f2r.dwROperand2 = dwROperand2; + + regm_MarkRegisterModified(pReg, dwRDest); + regm_MarkRegisterUsed(pReg, dwROperand2); +} + +/***********************************************************************/ +/* Immediate-to-register mov instructions (e.g, movi r1, 1) + * +/* FORM 2I: , +*/ + +void regm_GenerateForm2I(uint8_t chOp, uint32_t dwRDest, + uint32_t dwImmediate) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_2I; + pReg->chOp = chOp; + pReg->u.f2i.dwRDest = dwRDest; + pReg->u.f2i.dwImmediate = dwImmediate; + + regm_MarkRegisterModified(pReg, dwRDest); +} + +/***********************************************************************/ +/* Binary operations (e.g., add r0, r1, r2) + * Load operations (e.g., ld r0, [r1, r2]) + * Store operations (e.g., st r0, [r1, r2]) + * + * FORM 3R: , , + * , , + */ + +void regm_GenerateForm3R(uint8_t chOp, uint32_t dwRSrcDest, + uint32_t dwROperand1, uint32_t dwROperand2) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_3R; + pReg->chOp = chOp; + pReg->u.f3r.dwRSrcDest = dwRSrcDest; + pReg->u.f3r.dwROperand1 = dwROperand1; + pReg->u.f3r.dwROperand2 = dwROperand2; + + switch (chOp) + { + /* FORM 3: Arithmetic and logical operations */ + /* FORM 3: Loads */ + + case rADD : + case rSUB : + case rRSB : + case rMUL : + case rDIV : + case rMOD : + case rSLL : + case rSRL : + case rSRA : + case rOR : + case rAND : + case rXOR : + case rANDN : + case rLD : + case rLDH : + case rLDB : + regm_MarkRegisterModified(pReg, dwRSrcDest); + break; + + /* FORM 3: Loads multiple */ + case rLDM : + { + uint32_t dwRDest = dwRSrcDest; + int i; + for (i = 0; i < g_dwRegisterCount; i++) + { + regm_MarkRegisterModified(pReg, dwRDest); + dwRDest++; + } + } + break; + + /* FORM 3: Stores */ + case rST : + case rSTH : + case rSTB : + regm_MarkRegisterUsed(pReg, dwRSrcDest); + break; + + /* FORM 3: Store multipole */ + case rSTM : + { + uint32_t dwRSrc = dwRSrcDest; + int i; + for (i = 0; i < g_dwRegisterCount; i++) + { + regm_MarkRegisterUsed(pReg, dwRSrc); + dwRSrc++; + } + } + break; + + default: + fatal(ePOFFCONFUSION); + } + + regm_MarkRegisterUsed(pReg, dwROperand1); + regm_MarkRegisterUsed(pReg, dwROperand2); +} + +/***********************************************************************/ +/* Binary operations (e.g., addi r0, r1, 1) + * Load operations (e.g., ldi r0, [r1, 4]) + * Store operations (e.g., sti r0, [r1, 4]) + * + * FORM 3I: , , + * , , + */ + +void regm_GenerateForm3I(uint8_t chOp, uint32_t dwRSrcDest, + uint32_t dwROperand1, uint32_t dwImmediate) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_3I; + pReg->chOp = chOp; + pReg->u.f3i.dwRSrcDest = dwRSrcDest; + pReg->u.f3i.dwROperand1 = dwROperand1; + pReg->u.f3i.dwImmediate = dwImmediate; + + switch (chOp) + { + /* FORM 3: Arithmetic and logical operations */ + /* FORM 3: Loads */ + + case rADDI : + case rSUBI : + case rRSBI : + case rMULI : + case rDIVI : + case rMODI : + case rSLLI : + case rSRLI : + case rSRAI : + case rORI : + case rANDI : + case rXORI : + case rANDNI : + case rLDI : + case rLDIH : + case rLDIB : + regm_MarkRegisterModified(pReg, dwRSrcDest); + break; + + /* FORM 3: Stores */ + case rSTI : + case rSTIH : + case rSTIB : + regm_MarkRegisterUsed(pReg, dwRSrcDest); + break; + + default: + fatal(ePOFFCONFUSION); + } + + regm_MarkRegisterUsed(pReg, dwROperand1); +} + +/***********************************************************************/ +/* Unconditional branch operations (b offset, bl offset) + * + * FORM 4I: + */ + +void regm_GenerateForm4I(uint8_t chOp, uint32_t dwOffset) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_4I; + pReg->chOp = chOp; + pReg->u.f4i.dwOffset = dwOffset; +} + +/***********************************************************************/ +/* Conditional branch operations (e.g., beq offset) + * + * FORM 4I: + */ + +void regm_GenerateForm4ICc(uint8_t chOp, uint32_t dwOffset, + uint32_t dwRCc) +{ + struct regm_rcode2_s *pReg = regm_AllocateRCode2(); + pReg->eForm = eFORM_4ICc; + pReg->chOp = chOp; + pReg->u.f4icc.dwOffset = dwOffset; + pReg->u.f4icc.dwRCc = dwRCc; + + regm_MarkRegisterUsed(pReg, dwRCc); +} + +/***********************************************************************/ + +int regm_ForEachRCode2(regm_rcode2_node_t pNode, void *arg) +{ + int ret; + int i; + for (i = 0; i < g_nRCode2; i++) + { + ret = pNode(&g_pRCode2[i], arg); + if (ret != 0) + { + return ret; + } + } + return 0; +} + +/***********************************************************************/ diff --git a/misc/pascal/insn32/regm/regm_registers2.h b/misc/pascal/insn32/regm/regm_registers2.h index ec13e8cf2..eabe76f5b 100644 --- a/misc/pascal/insn32/regm/regm_registers2.h +++ b/misc/pascal/insn32/regm/regm_registers2.h @@ -1,317 +1,319 @@ -/*************************************************************************** - * regm_registers2.h - * Definitions for management of registers - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ***************************************************************************/ - -#ifndef __REGM_REGISTERS2_H -#define __REGM_REGISTERS2_H - -/*************************************************************************** - * Included Files - ***************************************************************************/ - -/*************************************************************************** - * Definitions - ***************************************************************************/ - -/* Register types */ - -#define NULL_REG 0 -#define SPECIAL_REG 1 /* Special "global" registers */ -#define CC_REG 2 /* Condition code register instance (fake) */ -#define ARG_REG 3 /* Volatile register for input arguments */ -#define INARG_REG ARG_REG /* from callee */ -#define OUTARG_REG 4 /* Volatile register for output arguments */ - /* to called function (fake) */ -#define RET_REG ARG_REG /* Volatile register for output values */ -#define OUTRET_REG ARG_REG /* to callee */ -#define INRET_REG OUTARG_REG /* Volatile register for input return */ - /* from called functions (fake) */ -#define SCRATCH_REG 5 /* Volatile register for general usage */ -#define VOLATILE_REG 6 /* Volatile registers in general */ -#define STATIC_REG 7 /* Static register */ - -#define NREGISTER_TYPES 8 - -/* Special registers */ - -#define SPB 0 /* 32-bit Pascal stack base address */ -#define SP 1 /* 32-bit Pascal stack pointer */ -#define BRG 2 /* 32-bit base register (related to parent level) */ -#define LSP 3 /* 32-bit Level stack pointer */ -#define CSB 4 /* 32-bit Character stack base address */ -#define CSP 5 /* 32-bit Character stack pointer */ -#define PC 6 /* 32-bit Program counter */ - -#define NSPECIAL_REGISTERS 7 - -#define DC 7 /* 32-bit Data count register -- disappears quickly */ -#define LR 8 /* 32-bit Link register -- same as SCRATCH(0) */ -#define CC 9 /* Condition code register -- not a normal register */ - -#define NSPECIAL_REGISTERS2 10 - -/* During pass2, we allow an indefinite number of registers. Eventually, - * these need to be compressed into a smaller number of registers. These - * define the number of registers available in the architecture. - */ - -#define NTOTAL_REGISTERS 32 -#define NGENERAL_REGISTERS (NTOTAL_REGISTERS-NSPECIAL_REGISTERS) -#define NARGUMENT_REGISTERS 4 -#define NSCRATCH_REGISTERS 4 -#define NVOLATILE_REGISTERS (NARGUMENT_REGISTERS+NSCRATCH_REGISTERS) -#define NSTATIC_REGISTERS (NGENERAL_REGISTERS-NVOLATILE_REGISTERS) - -/* Register creation macros */ - -#define MKSPECIAL(n) regm_MkRegister(SPECIAL_REG, (n)) -#define MKCC(n) regm_MkRegister(CC_REG, (n)) -#define MKINARG(n) regm_MkRegister(INARG_REG, (n)) -#define MKOUTARG(n) regm_MkRegister(OUTARG_REG, (n)) -#define MKINRET(n) regm_MkRegister(INRET_REG, (n)) -#define MKOUTRET(n) regm_MkRegister(OUTRET_REG, (n)) -#define MKSCRATCH(n) regm_MkRegister(SCRATCH_REG, (n)) -#define MKVOLATILE(n) regm_MkRegister(VOLATILE_REG, (n)) - -/* Make a register from a stack offset */ - -#define MKREG(n) MKSCRATCH((n) >> 2) -#define MKCCREG(n) MKCC((n) >> 2) - -/* Check register type */ - -#define ISSPECIAL(n) regm_IsKind(SPECIAL_REG, (n)) -#define ISCC(n) regm_IsKind(CC_REG, (n)) -#define ISARG(n) regm_IsKind(ARG_REG, (n)) -#define ISSCATCH(n) regm_IsKind(SCRATCH_REG, (n)) -#define ISVOLATILE(n) regm_IsKind(VOLATILE_REG, (n)) - -/*************************************************************************** - * Global Types - ***************************************************************************/ - -struct regm32_t -{ - uint32 kind : 3; /* Kind of register */ - uint32 regno : 29; /* Register identifier */ -}; - -union regm32_u -{ - struct regm32_t f; - uint32 dw; -}; - -enum regm_formtag_e -{ - eFORM_1RCc, /* , */ - eFORM_1ICc, /* , */ - eFORM_2R, /* , */ - eFORM_2I, /* , */ - eFORM_3R, /* , , */ - eFORM_3I, /* , , */ - eFORM_4I, /* */ - eFORM_4ICc, /* */ -}; - -struct regm_form1rcc_s -{ - uint32 dwROperand1, dwROperand2, dwRCc; -}; - -struct regm_form1icc_s -{ - uint32 dwROperand1, dwImmediate, dwRCc; -}; - -struct regm_form2r_s -{ - uint32 dwRDest, dwROperand2; -}; - -struct regm_form2i_s -{ - uint32 dwRDest, dwImmediate; -}; - -struct regm_form3r_s -{ - uint32 dwRSrcDest, dwROperand1, dwROperand2; -}; - -struct regm_form3i_s -{ - uint32 dwRSrcDest, dwROperand1, dwImmediate; -}; - -struct regm_form4i_s -{ - uint32 dwRDest, dwOffset; -}; - -struct regm_form4icc_s -{ - uint32 dwRDest, dwOffset, dwRCc; -}; - -struct regm_rcode2_s -{ - ubyte eForm; /* See enum regm_formtag_e */ - ubyte chOp; /* Regm opcode */ - union - { - struct regm_form1rcc_s f1rcc; - struct regm_form1icc_s f1icc; - struct regm_form2r_s f2r; - struct regm_form2i_s f2i; - struct regm_form3r_s f3r; - struct regm_form3i_s f3i; - struct regm_form4i_s f4i; - struct regm_form4icc_s f4icc; - } u; -}; - -typedef int (*regm_rcode2_node_t)(struct regm_rcode2_s*, void*); - -/*************************************************************************** - * Global Variables - ***************************************************************************/ - -extern struct regm_rcode2_s *g_pRCode2; -extern uint32 g_nRCode2; - -/*************************************************************************** - * Inline Functions - ***************************************************************************/ - -static inline uint32 regm_MkRegister(int wKind, int wRegNo) -{ - union regm32_u u; - u.f.kind = wKind; - u.f.regno = wRegNo; - return u.dw; -} - -static inline int regm_IsKind(int wKind, uint32 dwRegister) -{ - union regm32_u u; - u.dw = dwRegister; - return (u.f.kind == wKind); -} - -static inline int regm_GetKind(uint32 dwRegister) -{ - union regm32_u u; - u.dw = dwRegister; - return u.f.kind; -} - -static inline void regm_SetKind(int wKind, uint32 *pdwRegister) -{ - union regm32_u *pu = (union regm32_u *)pdwRegister; - pu->f.kind = wKind; -} - -static inline int regm_GetRegNo(uint32 dwRegister) -{ - union regm32_u u; - u.dw = dwRegister; - return u.f.regno; -} - -static inline void regm_SetRegNo(int wRegNo, uint32 *pdwRegister) -{ - union regm32_u *pu = (union regm32_u *)pdwRegister; - pu->f.regno = wRegNo; -} - -/*************************************************************************** - * Global Function Prototypes - ***************************C***********************************************/ - -/* Generate function prologue: Save return address, create stack frame - * for local variables, and save static registers that till be used. - */ - -extern void regm_GeneratePrologue(uint32 dwFrameSize); - -/* Restore static registers, release stack frame and return */ - -extern void regm_GenerateEpilogue(uint32 dwFrameSize); - -/* FORM 1R: , */ - -extern void regm_GenerateForm1RCc(ubyte chOp, uint32 dwROperand1, - uint32 dwROperand2, uint32 dwRCc); - -/* FORM 1I: , */ - -extern void regm_GenerateForm1ICc(ubyte chOp, uint32 dwROperand1, - uint32 dwImmediate, uint32 dwRCc); - -/* FORM 2R: , */ - -extern void regm_GenerateForm2R(ubyte chOp, uint32 dwRDest, - uint32 dwROperand2); - -/* FORM 2I: , */ - -extern void regm_GenerateForm2I(ubyte chOp, uint32 dwRDest, - uint32 dwImmediate); - -/* FORM 3R: , , - * , , - */ - -extern void regm_GenerateForm3R(ubyte chOp, uint32 dwRSrcDest, - uint32 dwROperand1, uint32 dwROperand2); - -/* FORM 3I: , , - * , , - */ - -extern void regm_GenerateForm3I(ubyte chOp, uint32 dwRSrcDest, - uint32 dwROperand1, uint32 dwImmediate); - -/* FORM 4I: */ - -extern void regm_GenerateForm4I(ubyte chOp, uint32 dwOffset); - -extern void regm_GenerateForm4ICc(ubyte chOp, uint32 dwOffset, - uint32 dwRCc); - -extern int regm_ForEachRCode2(regm_rcode2_node_t pNode, void *arg); - -#endif /* __REGM_REGISTERS2_H */ +/*************************************************************************** + * regm_registers2.h + * Definitions for management of registers + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ***************************************************************************/ + +#ifndef __REGM_REGISTERS2_H +#define __REGM_REGISTERS2_H + +/*************************************************************************** + * Included Files + ***************************************************************************/ + +#include + +/*************************************************************************** + * Definitions + ***************************************************************************/ + +/* Register types */ + +#define NULL_REG 0 +#define SPECIAL_REG 1 /* Special "global" registers */ +#define CC_REG 2 /* Condition code register instance (fake) */ +#define ARG_REG 3 /* Volatile register for input arguments */ +#define INARG_REG ARG_REG /* from callee */ +#define OUTARG_REG 4 /* Volatile register for output arguments */ + /* to called function (fake) */ +#define RET_REG ARG_REG /* Volatile register for output values */ +#define OUTRET_REG ARG_REG /* to callee */ +#define INRET_REG OUTARG_REG /* Volatile register for input return */ + /* from called functions (fake) */ +#define SCRATCH_REG 5 /* Volatile register for general usage */ +#define VOLATILE_REG 6 /* Volatile registers in general */ +#define STATIC_REG 7 /* Static register */ + +#define NREGISTER_TYPES 8 + +/* Special registers */ + +#define SPB 0 /* 32-bit Pascal stack base address */ +#define SP 1 /* 32-bit Pascal stack pointer */ +#define BRG 2 /* 32-bit base register (related to parent level) */ +#define LSP 3 /* 32-bit Level stack pointer */ +#define CSB 4 /* 32-bit Character stack base address */ +#define CSP 5 /* 32-bit Character stack pointer */ +#define PC 6 /* 32-bit Program counter */ + +#define NSPECIAL_REGISTERS 7 + +#define DC 7 /* 32-bit Data count register -- disappears quickly */ +#define LR 8 /* 32-bit Link register -- same as SCRATCH(0) */ +#define CC 9 /* Condition code register -- not a normal register */ + +#define NSPECIAL_REGISTERS2 10 + +/* During pass2, we allow an indefinite number of registers. Eventually, + * these need to be compressed into a smaller number of registers. These + * define the number of registers available in the architecture. + */ + +#define NTOTAL_REGISTERS 32 +#define NGENERAL_REGISTERS (NTOTAL_REGISTERS-NSPECIAL_REGISTERS) +#define NARGUMENT_REGISTERS 4 +#define NSCRATCH_REGISTERS 4 +#define NVOLATILE_REGISTERS (NARGUMENT_REGISTERS+NSCRATCH_REGISTERS) +#define NSTATIC_REGISTERS (NGENERAL_REGISTERS-NVOLATILE_REGISTERS) + +/* Register creation macros */ + +#define MKSPECIAL(n) regm_MkRegister(SPECIAL_REG, (n)) +#define MKCC(n) regm_MkRegister(CC_REG, (n)) +#define MKINARG(n) regm_MkRegister(INARG_REG, (n)) +#define MKOUTARG(n) regm_MkRegister(OUTARG_REG, (n)) +#define MKINRET(n) regm_MkRegister(INRET_REG, (n)) +#define MKOUTRET(n) regm_MkRegister(OUTRET_REG, (n)) +#define MKSCRATCH(n) regm_MkRegister(SCRATCH_REG, (n)) +#define MKVOLATILE(n) regm_MkRegister(VOLATILE_REG, (n)) + +/* Make a register from a stack offset */ + +#define MKREG(n) MKSCRATCH((n) >> 2) +#define MKCCREG(n) MKCC((n) >> 2) + +/* Check register type */ + +#define ISSPECIAL(n) regm_IsKind(SPECIAL_REG, (n)) +#define ISCC(n) regm_IsKind(CC_REG, (n)) +#define ISARG(n) regm_IsKind(ARG_REG, (n)) +#define ISSCATCH(n) regm_IsKind(SCRATCH_REG, (n)) +#define ISVOLATILE(n) regm_IsKind(VOLATILE_REG, (n)) + +/*************************************************************************** + * Global Types + ***************************************************************************/ + +struct regm32_t +{ + uint32_t kind : 3; /* Kind of register */ + uint32_t regno : 29; /* Register identifier */ +}; + +union regm32_u +{ + struct regm32_t f; + uint32_t dw; +}; + +enum regm_formtag_e +{ + eFORM_1RCc, /* , */ + eFORM_1ICc, /* , */ + eFORM_2R, /* , */ + eFORM_2I, /* , */ + eFORM_3R, /* , , */ + eFORM_3I, /* , , */ + eFORM_4I, /* */ + eFORM_4ICc, /* */ +}; + +struct regm_form1rcc_s +{ + uint32_t dwROperand1, dwROperand2, dwRCc; +}; + +struct regm_form1icc_s +{ + uint32_t dwROperand1, dwImmediate, dwRCc; +}; + +struct regm_form2r_s +{ + uint32_t dwRDest, dwROperand2; +}; + +struct regm_form2i_s +{ + uint32_t dwRDest, dwImmediate; +}; + +struct regm_form3r_s +{ + uint32_t dwRSrcDest, dwROperand1, dwROperand2; +}; + +struct regm_form3i_s +{ + uint32_t dwRSrcDest, dwROperand1, dwImmediate; +}; + +struct regm_form4i_s +{ + uint32_t dwRDest, dwOffset; +}; + +struct regm_form4icc_s +{ + uint32_t dwRDest, dwOffset, dwRCc; +}; + +struct regm_rcode2_s +{ + uint8_t eForm; /* See enum regm_formtag_e */ + uint8_t chOp; /* Regm opcode */ + union + { + struct regm_form1rcc_s f1rcc; + struct regm_form1icc_s f1icc; + struct regm_form2r_s f2r; + struct regm_form2i_s f2i; + struct regm_form3r_s f3r; + struct regm_form3i_s f3i; + struct regm_form4i_s f4i; + struct regm_form4icc_s f4icc; + } u; +}; + +typedef int (*regm_rcode2_node_t)(struct regm_rcode2_s*, void*); + +/*************************************************************************** + * Global Variables + ***************************************************************************/ + +extern struct regm_rcode2_s *g_pRCode2; +extern uint32_t g_nRCode2; + +/*************************************************************************** + * Inline Functions + ***************************************************************************/ + +static inline uint32_t regm_MkRegister(int wKind, int wRegNo) +{ + union regm32_u u; + u.f.kind = wKind; + u.f.regno = wRegNo; + return u.dw; +} + +static inline int regm_IsKind(int wKind, uint32_t dwRegister) +{ + union regm32_u u; + u.dw = dwRegister; + return (u.f.kind == wKind); +} + +static inline int regm_GetKind(uint32_t dwRegister) +{ + union regm32_u u; + u.dw = dwRegister; + return u.f.kind; +} + +static inline void regm_SetKind(int wKind, uint32_t *pdwRegister) +{ + union regm32_u *pu = (union regm32_u *)pdwRegister; + pu->f.kind = wKind; +} + +static inline int regm_GetRegNo(uint32_t dwRegister) +{ + union regm32_u u; + u.dw = dwRegister; + return u.f.regno; +} + +static inline void regm_SetRegNo(int wRegNo, uint32_t *pdwRegister) +{ + union regm32_u *pu = (union regm32_u *)pdwRegister; + pu->f.regno = wRegNo; +} + +/*************************************************************************** + * Global Function Prototypes + ***************************C***********************************************/ + +/* Generate function prologue: Save return address, create stack frame + * for local variables, and save static registers that till be used. + */ + +extern void regm_GeneratePrologue(uint32_t dwFrameSize); + +/* Restore static registers, release stack frame and return */ + +extern void regm_GenerateEpilogue(uint32_t dwFrameSize); + +/* FORM 1R: , */ + +extern void regm_GenerateForm1RCc(uint8_t chOp, uint32_t dwROperand1, + uint32_t dwROperand2, uint32_t dwRCc); + +/* FORM 1I: , */ + +extern void regm_GenerateForm1ICc(uint8_t chOp, uint32_t dwROperand1, + uint32_t dwImmediate, uint32_t dwRCc); + +/* FORM 2R: , */ + +extern void regm_GenerateForm2R(uint8_t chOp, uint32_t dwRDest, + uint32_t dwROperand2); + +/* FORM 2I: , */ + +extern void regm_GenerateForm2I(uint8_t chOp, uint32_t dwRDest, + uint32_t dwImmediate); + +/* FORM 3R: , , + * , , + */ + +extern void regm_GenerateForm3R(uint8_t chOp, uint32_t dwRSrcDest, + uint32_t dwROperand1, uint32_t dwROperand2); + +/* FORM 3I: , , + * , , + */ + +extern void regm_GenerateForm3I(uint8_t chOp, uint32_t dwRSrcDest, + uint32_t dwROperand1, uint32_t dwImmediate); + +/* FORM 4I: */ + +extern void regm_GenerateForm4I(uint8_t chOp, uint32_t dwOffset); + +extern void regm_GenerateForm4ICc(uint8_t chOp, uint32_t dwOffset, + uint32_t dwRCc); + +extern int regm_ForEachRCode2(regm_rcode2_node_t pNode, void *arg); + +#endif /* __REGM_REGISTERS2_H */ diff --git a/misc/pascal/insn32/regm/regm_tree.c b/misc/pascal/insn32/regm/regm_tree.c index e2fdff56b..0a59bbdbd 100644 --- a/misc/pascal/insn32/regm/regm_tree.c +++ b/misc/pascal/insn32/regm/regm_tree.c @@ -1,337 +1,338 @@ -/********************************************************************** - * regm_tree.c - * Tree managmenet - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - **********************************************************************/ - -/********************************************************************** - * Included Files - **********************************************************************/ - -#include -#include -#include - -#include "keywords.h" -#include "pdefs.h" /* Types needed for unused protos in pinsn.h */ -#include "podefs.h" /* Types needed for unused protos in pinsh.h */ -#include "pedefs.h" -#include "pofflib.h" -#include "paslib.h" -#include "pinsn.h" /* Folr insn_GetOpCode */ -#include "perr.h" - -#include "pinsn32.h" -#include "regm.h" -#include "regm_tree.h" - -/********************************************************************** - * Definitions - **********************************************************************/ - -#define INITIAL_PCODE_ALLOC 250 -#define PCODE_RELLALLOC 100 - -/********************************************************************** - * Private Types - **********************************************************************/ - -/********************************************************************** - * Private Function Prototypes - **********************************************************************/ - -/********************************************************************** - * Global Variables - **********************************************************************/ - -/********************************************************************** - * Private Variables - **********************************************************************/ - -static struct procdata_s *g_pProgramHead = NULL; - -/********************************************************************** - * Private Functions - **********************************************************************/ - -/***********************************************************************/ - -static inline void regm_DumpIndent(uint32 dwIndent) -{ - while (dwIndent--) putchar(' '); -} - -/***********************************************************************/ - -void regm_DumpNode(struct procdata_s *pNode, unsigned long dwIndent) -{ - if (pNode) - { - if (pNode->section[0].dwOffset != pNode->section[1].dwOffset) - { - regm_DumpIndent(dwIndent); - printf("%08lx:%08lx\n", - pNode->section[0].dwOffset, - pNode->section[0].dwOffset + pNode->section[0].dwSize - 1); - } - regm_DumpIndent(dwIndent); - printf("%08lx:%08lx\n", - pNode->section[1].dwOffset, - pNode->section[1].dwOffset + pNode->section[1].dwSize - 1); - - regm_DumpNode(pNode->child, dwIndent + 3); - regm_DumpNode(pNode->peer, dwIndent); - } -} - -/***********************************************************************/ - -/********************************************************************** - * Global Functions - **********************************************************************/ - -/***********************************************************************/ - -void regm_InitTree(void) -{ - g_pProgramHead = NULL; -} - -/***********************************************************************/ - -struct procdata_s *regm_CreateProgSection(void) -{ - struct procdata_s *pNode; - pNode = (struct procdata_s *)malloc(sizeof(struct procdata_s)); - if (!pNode) - { - fatal(eNOMEMORY); - } - memset(pNode, 0, sizeof(struct procdata_s)); - return pNode; -} - -/***********************************************************************/ - -void regm_SetProgRoot(struct procdata_s *pNode) -{ - g_pProgramHead = pNode; - pNode->child = NULL; - pNode->peer = NULL; -} - -/***********************************************************************/ - -void regm_AddProgChild(struct procdata_s *pParent, struct procdata_s *pNode) -{ - struct procdata_s *pPrev = pParent; - - /* Go to the end of the list */ - - while (pPrev->child != NULL) pPrev = pPrev->child; - - /* Deposit the new node at the end of the list */ - - pPrev->child = pNode; - pNode->child = NULL; - pNode->peer = NULL; -} - -/***********************************************************************/ - -void regm_AddProgPeer(struct procdata_s *pPeer, struct procdata_s *pNode) -{ - struct procdata_s *pPrev = pPeer; - - /* Go to the end of the list */ - - while (pPrev->peer != NULL) pPrev = pPrev->peer; - - /* Deposit the new node at the end of the list */ - - pPrev->peer = pNode; - pNode->child = NULL; - pNode->peer = NULL; -} - -/***********************************************************************/ - -struct procdata_s *regm_GetRootNode(void) -{ - return g_pProgramHead; -} - -/***********************************************************************/ - -int regm_ForEachPeer(struct procdata_s *pPeer, - int (*pfPeerFunc)(struct procdata_s*, void*), - void *arg) -{ - struct procdata_s *pCurr = pPeer; - struct procdata_s *pNext; - int retval; - - while (pCurr->peer) - { - pNext = pCurr->peer; - retval = pfPeerFunc(pCurr, arg); - if (retval) - { - return retval; - } - pCurr = pNext; - } - return 0; -} - -/***********************************************************************/ - -int regm_ForEachChild(struct procdata_s *pParent, - int (*pfChildFunc)(struct procdata_s*, void*), - void *arg) -{ - struct procdata_s *pCurr = pParent; - struct procdata_s *pNext; - int retval; - - while (pCurr->child) - { - pNext = pCurr->child; - retval = pfChildFunc(pCurr, arg); - if (retval) - { - return retval; - } - pCurr = pNext; - } - return 0; -} - -/***********************************************************************/ - -uint32 regm_ReadNodePCodes(struct procdata_s *pNode, poffHandle_t hPoff, - uint32 dwStartOffset, uint32 dwEndOffset, - ubyte cTerminalOpcode) -{ - uint32 dwOffset = dwStartOffset; - long nAlloc = INITIAL_PCODE_ALLOC; - long nPCodes; - ubyte bTerminatorFound; - - dbg("Reading Node: %08lx %08lx %02x\n", - dwStartOffset, dwEndOffset, cTerminalOpcode); - - /* Allocate an inital buffer to hold the instructions */ - - pNode->pPCode = (OPTYPE*) - malloc(INITIAL_PCODE_ALLOC*sizeof(struct procinsn_s*)); - if (!pNode->pPCode) - { - fatal(eNOMEMORY); - } - - /* Seek to the beginning of the data */ - - regm_ProgSeek(hPoff, dwStartOffset); - - /* Read all of the instructions in the main program section */ - - nPCodes = 0; - bTerminatorFound = 0; - do - { - /* Make sure that there is space for another pcode */ - - if (nPCodes > nAlloc) - { - /* If not, then reallocate the array */ - - nAlloc += PCODE_RELLALLOC; - pNode->pPCode = (OPTYPE*) - realloc(pNode->pPCode, nAlloc*sizeof(OPTYPE)); - } - - /* Ready the pcode ito the array */ - - dwOffset += insn_GetOpCode(hPoff, &pNode->pPCode[nPCodes]); - - /* Check for a terminating pcode */ - - if ((GETOP(&pNode->pPCode[nPCodes]) == cTerminalOpcode) || - (GETOP(&pNode->pPCode[nPCodes]) == oEND)) - { - bTerminatorFound++; - } - - /* Increment the count of pcodes read */ - - nPCodes++; - } - while (!bTerminatorFound && (dwOffset < dwEndOffset)); - - dbg(" %08lx %08lx %02x\n", - dwStartOffset, dwOffset, GETOP(&pNode->pPCode[nPCodes-1])); - - /* Save the number of pcodes that we found */ - - pNode->nPCodes = nPCodes; - - /* Check for the correct terminator */ - - if (GETOP(&pNode->pPCode[nPCodes-1]) != cTerminalOpcode) - { - fatal(ePOFFCONFUSION); - } - - /* Return any unused space in the allocation */ - - pNode->pPCode = (OPTYPE*) - realloc(pNode->pPCode, nPCodes*sizeof(OPTYPE)); - - /* Return the actual end offset */ - - return dwOffset; -} - -/***********************************************************************/ - -void regm_DumpTree(void) -{ - if (vRegmDebug) - { - regm_DumpNode(g_pProgramHead, 0); - } -} - -/***********************************************************************/ - +/********************************************************************** + * regm_tree.c + * Tree managmenet + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **********************************************************************/ + +/********************************************************************** + * Included Files + **********************************************************************/ + +#include +#include +#include +#include + +#include "keywords.h" +#include "pdefs.h" /* Types needed for unused protos in pinsn.h */ +#include "podefs.h" /* Types needed for unused protos in pinsh.h */ +#include "pedefs.h" +#include "pofflib.h" +#include "paslib.h" +#include "pinsn.h" /* Folr insn_GetOpCode */ +#include "perr.h" + +#include "pinsn32.h" +#include "regm.h" +#include "regm_tree.h" + +/********************************************************************** + * Definitions + **********************************************************************/ + +#define INITIAL_PCODE_ALLOC 250 +#define PCODE_RELLALLOC 100 + +/********************************************************************** + * Private Types + **********************************************************************/ + +/********************************************************************** + * Private Function Prototypes + **********************************************************************/ + +/********************************************************************** + * Global Variables + **********************************************************************/ + +/********************************************************************** + * Private Variables + **********************************************************************/ + +static struct procdata_s *g_pProgramHead = NULL; + +/********************************************************************** + * Private Functions + **********************************************************************/ + +/***********************************************************************/ + +static inline void regm_DumpIndent(uint32_t dwIndent) +{ + while (dwIndent--) putchar(' '); +} + +/***********************************************************************/ + +void regm_DumpNode(struct procdata_s *pNode, unsigned long dwIndent) +{ + if (pNode) + { + if (pNode->section[0].dwOffset != pNode->section[1].dwOffset) + { + regm_DumpIndent(dwIndent); + printf("%08lx:%08lx\n", + pNode->section[0].dwOffset, + pNode->section[0].dwOffset + pNode->section[0].dwSize - 1); + } + regm_DumpIndent(dwIndent); + printf("%08lx:%08lx\n", + pNode->section[1].dwOffset, + pNode->section[1].dwOffset + pNode->section[1].dwSize - 1); + + regm_DumpNode(pNode->child, dwIndent + 3); + regm_DumpNode(pNode->peer, dwIndent); + } +} + +/***********************************************************************/ + +/********************************************************************** + * Global Functions + **********************************************************************/ + +/***********************************************************************/ + +void regm_InitTree(void) +{ + g_pProgramHead = NULL; +} + +/***********************************************************************/ + +struct procdata_s *regm_CreateProgSection(void) +{ + struct procdata_s *pNode; + pNode = (struct procdata_s *)malloc(sizeof(struct procdata_s)); + if (!pNode) + { + fatal(eNOMEMORY); + } + memset(pNode, 0, sizeof(struct procdata_s)); + return pNode; +} + +/***********************************************************************/ + +void regm_SetProgRoot(struct procdata_s *pNode) +{ + g_pProgramHead = pNode; + pNode->child = NULL; + pNode->peer = NULL; +} + +/***********************************************************************/ + +void regm_AddProgChild(struct procdata_s *pParent, struct procdata_s *pNode) +{ + struct procdata_s *pPrev = pParent; + + /* Go to the end of the list */ + + while (pPrev->child != NULL) pPrev = pPrev->child; + + /* Deposit the new node at the end of the list */ + + pPrev->child = pNode; + pNode->child = NULL; + pNode->peer = NULL; +} + +/***********************************************************************/ + +void regm_AddProgPeer(struct procdata_s *pPeer, struct procdata_s *pNode) +{ + struct procdata_s *pPrev = pPeer; + + /* Go to the end of the list */ + + while (pPrev->peer != NULL) pPrev = pPrev->peer; + + /* Deposit the new node at the end of the list */ + + pPrev->peer = pNode; + pNode->child = NULL; + pNode->peer = NULL; +} + +/***********************************************************************/ + +struct procdata_s *regm_GetRootNode(void) +{ + return g_pProgramHead; +} + +/***********************************************************************/ + +int regm_ForEachPeer(struct procdata_s *pPeer, + int (*pfPeerFunc)(struct procdata_s*, void*), + void *arg) +{ + struct procdata_s *pCurr = pPeer; + struct procdata_s *pNext; + int retval; + + while (pCurr->peer) + { + pNext = pCurr->peer; + retval = pfPeerFunc(pCurr, arg); + if (retval) + { + return retval; + } + pCurr = pNext; + } + return 0; +} + +/***********************************************************************/ + +int regm_ForEachChild(struct procdata_s *pParent, + int (*pfChildFunc)(struct procdata_s*, void*), + void *arg) +{ + struct procdata_s *pCurr = pParent; + struct procdata_s *pNext; + int retval; + + while (pCurr->child) + { + pNext = pCurr->child; + retval = pfChildFunc(pCurr, arg); + if (retval) + { + return retval; + } + pCurr = pNext; + } + return 0; +} + +/***********************************************************************/ + +uint32_t regm_ReadNodePCodes(struct procdata_s *pNode, poffHandle_t hPoff, + uint32_t dwStartOffset, uint32_t dwEndOffset, + uint8_t cTerminalOpcode) +{ + uint32_t dwOffset = dwStartOffset; + long nAlloc = INITIAL_PCODE_ALLOC; + long nPCodes; + uint8_t bTerminatorFound; + + dbg("Reading Node: %08lx %08lx %02x\n", + dwStartOffset, dwEndOffset, cTerminalOpcode); + + /* Allocate an inital buffer to hold the instructions */ + + pNode->pPCode = (OPTYPE*) + malloc(INITIAL_PCODE_ALLOC*sizeof(struct procinsn_s*)); + if (!pNode->pPCode) + { + fatal(eNOMEMORY); + } + + /* Seek to the beginning of the data */ + + regm_ProgSeek(hPoff, dwStartOffset); + + /* Read all of the instructions in the main program section */ + + nPCodes = 0; + bTerminatorFound = 0; + do + { + /* Make sure that there is space for another pcode */ + + if (nPCodes > nAlloc) + { + /* If not, then reallocate the array */ + + nAlloc += PCODE_RELLALLOC; + pNode->pPCode = (OPTYPE*) + realloc(pNode->pPCode, nAlloc*sizeof(OPTYPE)); + } + + /* Ready the pcode ito the array */ + + dwOffset += insn_GetOpCode(hPoff, &pNode->pPCode[nPCodes]); + + /* Check for a terminating pcode */ + + if ((GETOP(&pNode->pPCode[nPCodes]) == cTerminalOpcode) || + (GETOP(&pNode->pPCode[nPCodes]) == oEND)) + { + bTerminatorFound++; + } + + /* Increment the count of pcodes read */ + + nPCodes++; + } + while (!bTerminatorFound && (dwOffset < dwEndOffset)); + + dbg(" %08lx %08lx %02x\n", + dwStartOffset, dwOffset, GETOP(&pNode->pPCode[nPCodes-1])); + + /* Save the number of pcodes that we found */ + + pNode->nPCodes = nPCodes; + + /* Check for the correct terminator */ + + if (GETOP(&pNode->pPCode[nPCodes-1]) != cTerminalOpcode) + { + fatal(ePOFFCONFUSION); + } + + /* Return any unused space in the allocation */ + + pNode->pPCode = (OPTYPE*) + realloc(pNode->pPCode, nPCodes*sizeof(OPTYPE)); + + /* Return the actual end offset */ + + return dwOffset; +} + +/***********************************************************************/ + +void regm_DumpTree(void) +{ + if (vRegmDebug) + { + regm_DumpNode(g_pProgramHead, 0); + } +} + +/***********************************************************************/ + diff --git a/misc/pascal/insn32/regm/regm_tree.h b/misc/pascal/insn32/regm/regm_tree.h index bcc869890..0d6336d74 100644 --- a/misc/pascal/insn32/regm/regm_tree.h +++ b/misc/pascal/insn32/regm/regm_tree.h @@ -1,121 +1,122 @@ -/*************************************************************************** - * regm_tree.h - * External Declarations associated with regm_tree.c - * - * Copyright (C) 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ***************************************************************************/ - -#ifndef __REGM_TREE_H -#define __REGM_TREE_H - -/*************************************************************************** - * Included Files - ***************************************************************************/ - -#include "keywords.h" -#include "pofflib.h" -#include "rinsn32.h" - -/*************************************************************************** - * Definitions - ***************************************************************************/ - -/*************************************************************************** - * Global Types - ***************************************************************************/ - -/* This structure retains information about a specific function */ - -struct procinsn_s -{ - RINSN32 sRegOp; - uint32 dwRegModified; - uint32 dwRegsUsed[2]; -}; - -/* Each program section is described by an entry point offset, a - * file offset, a size in bytes, and a list of instructions (but - * we ignore the instructions at the trivial entry point which - * will be one or zero pcodes). - */ - -struct procsection_s -{ - uint32 dwOffset; /* File offset to section */ - uint32 dwSize; /* Size of section in bytes */ -}; - -/* But each pascal procedure may contain two program sections: - * one before any nested functions/procedures. and one for the - * main body. - */ - -struct procdata_s -{ - struct procdata_s *peer; /* Next proc/func at this level */ - struct procdata_s *child; /* First nested proc/func */ - struct procsection_s section[2]; - poffLibDebugFuncInfo_t *pFuncInfo; - int nPCodes; - OPTYPE *pPCode; - struct procinsn_s *pRegOps; -}; - -/*************************************************************************** - * Global Variables - ***************************************************************************/ - -/*************************************************************************** - * Global Function Prototypes - ***************************************************************************/ - -extern void regm_InitTree(void); -extern struct procdata_s *regm_CreateProgSection(void); -extern void regm_SetProgRoot(struct procdata_s *pNode); -extern void regm_AddProgChild(struct procdata_s *pParent, - struct procdata_s *pNode); -extern void regm_AddProgPeer(struct procdata_s *pPeer, - struct procdata_s *pNode); -extern struct procdata_s *regm_GetRootNode(void); -extern int regm_ForEachPeer(struct procdata_s *pPeer, - int (*pfPeerFunc)(struct procdata_s*, void*), - void *arg); -extern int regm_ForEachChild(struct procdata_s *pParent, - int (*pfChildFunc)(struct procdata_s*, void*), - void *arg); -extern uint32 regm_ReadNodePCodes(struct procdata_s *pNode, - poffHandle_t hPoff, - uint32 dwStartOffset, uint32 dwEndOffset, - ubyte cTerminalOpcode); -extern void regm_DumpTree(void); - -#endif /* __REGM_TREE_H */ +/*************************************************************************** + * regm_tree.h + * External Declarations associated with regm_tree.c + * + * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ***************************************************************************/ + +#ifndef __REGM_TREE_H +#define __REGM_TREE_H + +/*************************************************************************** + * Included Files + ***************************************************************************/ + +#include +#include "keywords.h" +#include "pofflib.h" +#include "rinsn32.h" + +/*************************************************************************** + * Definitions + ***************************************************************************/ + +/*************************************************************************** + * Global Types + ***************************************************************************/ + +/* This structure retains information about a specific function */ + +struct procinsn_s +{ + RINSN32 sRegOp; + uint32_t dwRegModified; + uint32_t dwRegsUsed[2]; +}; + +/* Each program section is described by an entry point offset, a + * file offset, a size in bytes, and a list of instructions (but + * we ignore the instructions at the trivial entry point which + * will be one or zero pcodes). + */ + +struct procsection_s +{ + uint32_t dwOffset; /* File offset to section */ + uint32_t dwSize; /* Size of section in bytes */ +}; + +/* But each pascal procedure may contain two program sections: + * one before any nested functions/procedures. and one for the + * main body. + */ + +struct procdata_s +{ + struct procdata_s *peer; /* Next proc/func at this level */ + struct procdata_s *child; /* First nested proc/func */ + struct procsection_s section[2]; + poffLibDebugFuncInfo_t *pFuncInfo; + int nPCodes; + OPTYPE *pPCode; + struct procinsn_s *pRegOps; +}; + +/*************************************************************************** + * Global Variables + ***************************************************************************/ + +/*************************************************************************** + * Global Function Prototypes + ***************************************************************************/ + +extern void regm_InitTree(void); +extern struct procdata_s *regm_CreateProgSection(void); +extern void regm_SetProgRoot(struct procdata_s *pNode); +extern void regm_AddProgChild(struct procdata_s *pParent, + struct procdata_s *pNode); +extern void regm_AddProgPeer(struct procdata_s *pPeer, + struct procdata_s *pNode); +extern struct procdata_s *regm_GetRootNode(void); +extern int regm_ForEachPeer(struct procdata_s *pPeer, + int (*pfPeerFunc)(struct procdata_s*, void*), + void *arg); +extern int regm_ForEachChild(struct procdata_s *pParent, + int (*pfChildFunc)(struct procdata_s*, void*), + void *arg); +extern uint32_t regm_ReadNodePCodes(struct procdata_s *pNode, + poffHandle_t hPoff, + uint32_t dwStartOffset, uint32_t dwEndOffset, + uint8_t cTerminalOpcode); +extern void regm_DumpTree(void); + +#endif /* __REGM_TREE_H */ -- cgit v1.2.3