aboutsummaryrefslogtreecommitdiff
path: root/flang
diff options
context:
space:
mode:
Diffstat (limited to 'flang')
-rw-r--r--flang/include/flang/Lower/ConvertExpr.h1
-rw-r--r--flang/include/flang/Lower/ConvertVariable.h4
-rw-r--r--flang/include/flang/Optimizer/Builder/Runtime/Pointer.h30
-rw-r--r--flang/lib/Lower/Bridge.cpp2
-rw-r--r--flang/lib/Lower/ConvertExpr.cpp19
-rw-r--r--flang/lib/Lower/ConvertExprToHLFIR.cpp31
-rw-r--r--flang/lib/Lower/ConvertVariable.cpp60
-rw-r--r--flang/lib/Optimizer/Builder/CMakeLists.txt1
-rw-r--r--flang/lib/Optimizer/Builder/Runtime/Pointer.cpp27
-rw-r--r--flang/test/Lower/HLFIR/cray-pointers.f90195
10 files changed, 351 insertions, 19 deletions
diff --git a/flang/include/flang/Lower/ConvertExpr.h b/flang/include/flang/Lower/ConvertExpr.h
index 64a1809..386a0d4 100644
--- a/flang/include/flang/Lower/ConvertExpr.h
+++ b/flang/include/flang/Lower/ConvertExpr.h
@@ -234,7 +234,6 @@ inline mlir::NamedAttribute getAdaptToByRefAttr(fir::FirOpBuilder &builder) {
builder.getUnitAttr()};
}
-Fortran::semantics::SymbolRef getPointer(Fortran::semantics::SymbolRef sym);
mlir::Value addCrayPointerInst(mlir::Location loc, fir::FirOpBuilder &builder,
mlir::Value ptrVal, mlir::Type ptrTy,
mlir::Type pteTy);
diff --git a/flang/include/flang/Lower/ConvertVariable.h b/flang/include/flang/Lower/ConvertVariable.h
index 88e5e52..da7daef 100644
--- a/flang/include/flang/Lower/ConvertVariable.h
+++ b/flang/include/flang/Lower/ConvertVariable.h
@@ -125,5 +125,9 @@ void genDeclareSymbol(Fortran::lower::AbstractConverter &converter,
const Fortran::semantics::Symbol &sym,
const fir::ExtendedValue &exv, bool force = false);
+/// For the given Cray pointee symbol return the corresponding
+/// Cray pointer symbol. Assert if the pointer symbol cannot be found.
+Fortran::semantics::SymbolRef getCrayPointer(Fortran::semantics::SymbolRef sym);
+
} // namespace Fortran::lower
#endif // FORTRAN_LOWER_CONVERT_VARIABLE_H
diff --git a/flang/include/flang/Optimizer/Builder/Runtime/Pointer.h b/flang/include/flang/Optimizer/Builder/Runtime/Pointer.h
new file mode 100644
index 0000000..507bb98
--- /dev/null
+++ b/flang/include/flang/Optimizer/Builder/Runtime/Pointer.h
@@ -0,0 +1,30 @@
+//===-- Pointer.h - generate pointer runtime API calls-----------*- C++ -*-===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef FORTRAN_OPTIMIZER_BUILDER_RUNTIME_POINTER_H
+#define FORTRAN_OPTIMIZER_BUILDER_RUNTIME_POINTER_H
+
+#include "mlir/IR/Value.h"
+
+namespace mlir {
+class Location;
+} // namespace mlir
+
+namespace fir {
+class FirOpBuilder;
+}
+
+namespace fir::runtime {
+
+/// Generate runtime call to associate \p target address of scalar
+/// with the \p desc pointer descriptor.
+void genPointerAssociateScalar(fir::FirOpBuilder &builder, mlir::Location loc,
+ mlir::Value desc, mlir::Value target);
+
+} // namespace fir::runtime
+#endif // FORTRAN_OPTIMIZER_BUILDER_RUNTIME_POINTER_H
diff --git a/flang/lib/Lower/Bridge.cpp b/flang/lib/Lower/Bridge.cpp
index d7dec54c..0f86f90 100644
--- a/flang/lib/Lower/Bridge.cpp
+++ b/flang/lib/Lower/Bridge.cpp
@@ -3629,7 +3629,7 @@ private:
sym->Rank() == 0) {
// get the corresponding Cray pointer
- auto ptrSym = Fortran::lower::getPointer(*sym);
+ auto ptrSym = Fortran::lower::getCrayPointer(*sym);
fir::ExtendedValue ptr =
getSymbolExtendedValue(ptrSym, nullptr);
mlir::Value ptrVal = fir::getBase(ptr);
diff --git a/flang/lib/Lower/ConvertExpr.cpp b/flang/lib/Lower/ConvertExpr.cpp
index 191319c..a9298be 100644
--- a/flang/lib/Lower/ConvertExpr.cpp
+++ b/flang/lib/Lower/ConvertExpr.cpp
@@ -863,7 +863,7 @@ public:
addr);
} else if (sym->test(Fortran::semantics::Symbol::Flag::CrayPointee)) {
// get the corresponding Cray pointer
- auto ptrSym = Fortran::lower::getPointer(sym);
+ auto ptrSym = Fortran::lower::getCrayPointer(sym);
ExtValue ptr = gen(ptrSym);
mlir::Value ptrVal = fir::getBase(ptr);
mlir::Type ptrTy = converter.genType(*ptrSym);
@@ -1571,7 +1571,7 @@ public:
auto baseSym = getFirstSym(aref);
if (baseSym.test(Fortran::semantics::Symbol::Flag::CrayPointee)) {
// get the corresponding Cray pointer
- auto ptrSym = Fortran::lower::getPointer(baseSym);
+ auto ptrSym = Fortran::lower::getCrayPointer(baseSym);
fir::ExtendedValue ptr = gen(ptrSym);
mlir::Value ptrVal = fir::getBase(ptr);
@@ -6974,7 +6974,7 @@ private:
ComponentPath &components) {
mlir::Value ptrVal = nullptr;
if (x.test(Fortran::semantics::Symbol::Flag::CrayPointee)) {
- auto ptrSym = Fortran::lower::getPointer(x);
+ auto ptrSym = Fortran::lower::getCrayPointer(x);
ExtValue ptr = converter.getSymbolExtendedValue(ptrSym);
ptrVal = fir::getBase(ptr);
}
@@ -7629,19 +7629,6 @@ void Fortran::lower::createArrayMergeStores(
esp.incrementCounter();
}
-Fortran::semantics::SymbolRef
-Fortran::lower::getPointer(Fortran::semantics::SymbolRef sym) {
- assert(!sym->owner().crayPointers().empty() &&
- "empty Cray pointer/pointee map");
- for (const auto &[pointee, pointer] : sym->owner().crayPointers()) {
- if (pointee == sym->name()) {
- Fortran::semantics::SymbolRef v{pointer.get()};
- return v;
- }
- }
- llvm_unreachable("corresponding Cray pointer cannot be found");
-}
-
mlir::Value Fortran::lower::addCrayPointerInst(mlir::Location loc,
fir::FirOpBuilder &builder,
mlir::Value ptrVal,
diff --git a/flang/lib/Lower/ConvertExprToHLFIR.cpp b/flang/lib/Lower/ConvertExprToHLFIR.cpp
index 7305215..ee4d307 100644
--- a/flang/lib/Lower/ConvertExprToHLFIR.cpp
+++ b/flang/lib/Lower/ConvertExprToHLFIR.cpp
@@ -28,6 +28,7 @@
#include "flang/Optimizer/Builder/MutableBox.h"
#include "flang/Optimizer/Builder/Runtime/Character.h"
#include "flang/Optimizer/Builder/Runtime/Derived.h"
+#include "flang/Optimizer/Builder/Runtime/Pointer.h"
#include "flang/Optimizer/Builder/Todo.h"
#include "flang/Optimizer/HLFIR/HLFIROps.h"
#include "llvm/ADT/TypeSwitch.h"
@@ -268,8 +269,36 @@ private:
fir::FortranVariableOpInterface
gen(const Fortran::evaluate::SymbolRef &symbolRef) {
if (std::optional<fir::FortranVariableOpInterface> varDef =
- getSymMap().lookupVariableDefinition(symbolRef))
+ getSymMap().lookupVariableDefinition(symbolRef)) {
+ if (symbolRef->test(Fortran::semantics::Symbol::Flag::CrayPointee)) {
+ // The pointee is represented with a descriptor inheriting
+ // the shape and type parameters of the pointee.
+ // We have to update the base_addr to point to the current
+ // value of the Cray pointer variable.
+ fir::FirOpBuilder &builder = getBuilder();
+ fir::FortranVariableOpInterface ptrVar =
+ gen(Fortran::lower::getCrayPointer(symbolRef));
+ mlir::Value ptrAddr = ptrVar.getBase();
+
+ // Reinterpret the reference to a Cray pointer so that
+ // we have a pointer-compatible value after loading
+ // the Cray pointer value.
+ mlir::Type refPtrType = builder.getRefType(
+ fir::PointerType::get(fir::dyn_cast_ptrEleTy(ptrAddr.getType())));
+ mlir::Value cast = builder.createConvert(loc, refPtrType, ptrAddr);
+ mlir::Value ptrVal = builder.create<fir::LoadOp>(loc, cast);
+
+ // Update the base_addr to the value of the Cray pointer.
+ // This is a hacky way to do the update, and it may harm
+ // performance around Cray pointer references.
+ // TODO: we should introduce an operation that updates
+ // just the base_addr of the given box. The CodeGen
+ // will just convert it into a single store.
+ fir::runtime::genPointerAssociateScalar(builder, loc, varDef->getBase(),
+ ptrVal);
+ }
return *varDef;
+ }
TODO(getLoc(), "lowering symbol to HLFIR");
}
diff --git a/flang/lib/Lower/ConvertVariable.cpp b/flang/lib/Lower/ConvertVariable.cpp
index 15731f1..726b848 100644
--- a/flang/lib/Lower/ConvertVariable.cpp
+++ b/flang/lib/Lower/ConvertVariable.cpp
@@ -1477,6 +1477,8 @@ static void genDeclareSymbol(Fortran::lower::AbstractConverter &converter,
if (converter.getLoweringOptions().getLowerToHighLevelFIR() &&
!Fortran::semantics::IsProcedure(sym) &&
!sym.detailsIf<Fortran::semantics::CommonBlockDetails>()) {
+ bool isCrayPointee =
+ sym.test(Fortran::semantics::Symbol::Flag::CrayPointee);
fir::FirOpBuilder &builder = converter.getFirOpBuilder();
const mlir::Location loc = genLocation(converter, sym);
mlir::Value shapeOrShift;
@@ -1492,6 +1494,51 @@ static void genDeclareSymbol(Fortran::lower::AbstractConverter &converter,
auto name = converter.mangleName(sym);
fir::FortranVariableFlagsAttr attributes =
Fortran::lower::translateSymbolAttributes(builder.getContext(), sym);
+
+ if (isCrayPointee) {
+ mlir::Type baseType =
+ hlfir::getFortranElementOrSequenceType(base.getType());
+ if (auto seqType = mlir::dyn_cast<fir::SequenceType>(baseType)) {
+ // The pointer box's sequence type must be with unknown shape.
+ llvm::SmallVector<int64_t> shape(seqType.getDimension(),
+ fir::SequenceType::getUnknownExtent());
+ baseType = fir::SequenceType::get(shape, seqType.getEleTy());
+ }
+ fir::BoxType ptrBoxType =
+ fir::BoxType::get(fir::PointerType::get(baseType));
+ mlir::Value boxAlloc = builder.createTemporary(loc, ptrBoxType);
+
+ // Declare a local pointer variable.
+ attributes = fir::FortranVariableFlagsAttr::get(
+ builder.getContext(), fir::FortranVariableFlagsEnum::pointer);
+ auto newBase = builder.create<hlfir::DeclareOp>(
+ loc, boxAlloc, name, /*shape=*/nullptr, lenParams, attributes);
+ mlir::Value nullAddr =
+ builder.createNullConstant(loc, ptrBoxType.getEleTy());
+
+ // If the element type is known-length character, then
+ // EmboxOp does not need the length parameters.
+ if (auto charType = mlir::dyn_cast<fir::CharacterType>(
+ fir::unwrapSequenceType(baseType)))
+ if (!charType.hasDynamicLen())
+ lenParams.clear();
+
+ // Inherit the shape (and maybe length parameters) from the pointee
+ // declaration.
+ mlir::Value initVal =
+ builder.create<fir::EmboxOp>(loc, ptrBoxType, nullAddr, shapeOrShift,
+ /*slice=*/nullptr, lenParams);
+ builder.create<fir::StoreOp>(loc, initVal, newBase.getBase());
+
+ // Any reference to the pointee is going to be using the pointer
+ // box from now on. The base_addr of the descriptor must be updated
+ // to hold the value of the Cray pointer at the point of the pointee
+ // access.
+ // Note that the same Cray pointer may be associated with
+ // multiple pointees and each of them has its own descriptor.
+ symMap.addVariableDefinition(sym, newBase, force);
+ return;
+ }
auto newBase = builder.create<hlfir::DeclareOp>(
loc, base, name, shapeOrShift, lenParams, attributes);
symMap.addVariableDefinition(sym, newBase, force);
@@ -2056,3 +2103,16 @@ void Fortran::lower::createRuntimeTypeInfoGlobal(
mlir::StringAttr linkage = getLinkageAttribute(builder, var);
defineGlobal(converter, var, globalName, linkage);
}
+
+Fortran::semantics::SymbolRef
+Fortran::lower::getCrayPointer(Fortran::semantics::SymbolRef sym) {
+ assert(!sym->owner().crayPointers().empty() &&
+ "empty Cray pointer/pointee map");
+ for (const auto &[pointee, pointer] : sym->owner().crayPointers()) {
+ if (pointee == sym->name()) {
+ Fortran::semantics::SymbolRef v{pointer.get()};
+ return v;
+ }
+ }
+ llvm_unreachable("corresponding Cray pointer cannot be found");
+}
diff --git a/flang/lib/Optimizer/Builder/CMakeLists.txt b/flang/lib/Optimizer/Builder/CMakeLists.txt
index 7665ca1..5e5daffd3 100644
--- a/flang/lib/Optimizer/Builder/CMakeLists.txt
+++ b/flang/lib/Optimizer/Builder/CMakeLists.txt
@@ -22,6 +22,7 @@ add_flang_library(FIRBuilder
Runtime/Inquiry.cpp
Runtime/Intrinsics.cpp
Runtime/Numeric.cpp
+ Runtime/Pointer.cpp
Runtime/Ragged.cpp
Runtime/Reduction.cpp
Runtime/Stop.cpp
diff --git a/flang/lib/Optimizer/Builder/Runtime/Pointer.cpp b/flang/lib/Optimizer/Builder/Runtime/Pointer.cpp
new file mode 100644
index 0000000..160c651
--- /dev/null
+++ b/flang/lib/Optimizer/Builder/Runtime/Pointer.cpp
@@ -0,0 +1,27 @@
+//===-- Pointer.cpp -- generate pointer runtime API calls------------------===//
+//
+// Part of the LLVM Project, under the Apache License v2.0 with LLVM Exceptions.
+// See https://llvm.org/LICENSE.txt for license information.
+// SPDX-License-Identifier: Apache-2.0 WITH LLVM-exception
+//
+//===----------------------------------------------------------------------===//
+
+#include "flang/Optimizer/Builder/Runtime/Pointer.h"
+#include "flang/Optimizer/Builder/FIRBuilder.h"
+#include "flang/Optimizer/Builder/Runtime/RTBuilder.h"
+#include "flang/Runtime/pointer.h"
+
+using namespace Fortran::runtime;
+
+void fir::runtime::genPointerAssociateScalar(fir::FirOpBuilder &builder,
+ mlir::Location loc,
+ mlir::Value desc,
+ mlir::Value target) {
+ mlir::func::FuncOp func{
+ fir::runtime::getRuntimeFunc<mkRTKey(PointerAssociateScalar)>(loc,
+ builder)};
+ mlir::FunctionType fTy{func.getFunctionType()};
+ llvm::SmallVector<mlir::Value> args{
+ fir::runtime::createArguments(builder, loc, fTy, desc, target)};
+ builder.create<fir::CallOp>(loc, func, args);
+}
diff --git a/flang/test/Lower/HLFIR/cray-pointers.f90 b/flang/test/Lower/HLFIR/cray-pointers.f90
new file mode 100644
index 0000000..761fbba
--- /dev/null
+++ b/flang/test/Lower/HLFIR/cray-pointers.f90
@@ -0,0 +1,195 @@
+! Test lowering of Cray pointee references.
+! RUN: bbc -emit-hlfir -o - -I nowhere %s 2>&1 | FileCheck %s
+
+
+subroutine test1()
+ real x(10), res
+ pointer (cp, x)
+ res = x(7)
+end subroutine test1
+! CHECK-LABEL: func.func @_QPtest1() {
+! CHECK: %[[VAL_0:.*]] = fir.alloca !fir.box<!fir.ptr<!fir.array<?xf32>>>
+! CHECK: %[[VAL_1:.*]] = fir.alloca i64 {bindc_name = "cp", uniq_name = "_QFtest1Ecp"}
+! CHECK: %[[VAL_2:.*]]:2 = hlfir.declare %[[VAL_1]] {uniq_name = "_QFtest1Ecp"} : (!fir.ref<i64>) -> (!fir.ref<i64>, !fir.ref<i64>)
+! CHECK: %[[VAL_5:.*]] = arith.constant 10 : index
+! CHECK: %[[VAL_7:.*]] = fir.shape %[[VAL_5]] : (index) -> !fir.shape<1>
+! CHECK: %[[VAL_12:.*]]:2 = hlfir.declare %[[VAL_0]] {fortran_attrs = #fir.var_attrs<pointer>, uniq_name = "_QFtest1Ex"} : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>) -> (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>, !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>)
+! CHECK: %[[VAL_13:.*]] = fir.zero_bits !fir.ptr<!fir.array<?xf32>>
+! CHECK: %[[VAL_14:.*]] = fir.embox %[[VAL_13]](%[[VAL_7]]) : (!fir.ptr<!fir.array<?xf32>>, !fir.shape<1>) -> !fir.box<!fir.ptr<!fir.array<?xf32>>>
+! CHECK: fir.store %[[VAL_14]] to %[[VAL_12]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>
+! CHECK: %[[VAL_15:.*]] = fir.convert %[[VAL_2]]#0 : (!fir.ref<i64>) -> !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_16:.*]] = fir.load %[[VAL_15]] : !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_17:.*]] = fir.convert %[[VAL_12]]#0 : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>) -> !fir.ref<!fir.box<none>>
+! CHECK: %[[VAL_18:.*]] = fir.convert %[[VAL_16]] : (!fir.ptr<i64>) -> !fir.llvm_ptr<i8>
+! CHECK: %[[VAL_19:.*]] = fir.call @_FortranAPointerAssociateScalar(%[[VAL_17]], %[[VAL_18]]) fastmath<contract> : (!fir.ref<!fir.box<none>>, !fir.llvm_ptr<i8>) -> none
+! CHECK: %[[VAL_20:.*]] = fir.load %[[VAL_12]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>
+! CHECK: %[[VAL_21:.*]] = arith.constant 7 : index
+! CHECK: %[[VAL_22:.*]] = hlfir.designate %[[VAL_20]] (%[[VAL_21]]) : (!fir.box<!fir.ptr<!fir.array<?xf32>>>, index) -> !fir.ref<f32>
+
+
+subroutine test2(n)
+ integer n
+ real x
+ pointer (cp, x(3:n))
+ res = x(7)
+end subroutine test2
+! CHECK-LABEL: func.func @_QPtest2(
+! CHECK-SAME: %[[VAL_0:.*]]: !fir.ref<i32> {fir.bindc_name = "n"}) {
+! CHECK: %[[VAL_1:.*]] = fir.alloca !fir.box<!fir.ptr<!fir.array<?xf32>>>
+! CHECK: %[[VAL_2:.*]] = fir.alloca i64 {bindc_name = "cp", uniq_name = "_QFtest2Ecp"}
+! CHECK: %[[VAL_3:.*]]:2 = hlfir.declare %[[VAL_2]] {uniq_name = "_QFtest2Ecp"} : (!fir.ref<i64>) -> (!fir.ref<i64>, !fir.ref<i64>)
+! CHECK: %[[VAL_19:.*]] = fir.shape_shift %{{.*}}, %{{.*}} : (index, index) -> !fir.shapeshift<1>
+! CHECK: %[[VAL_24:.*]]:2 = hlfir.declare %[[VAL_1]] {fortran_attrs = #fir.var_attrs<pointer>, uniq_name = "_QFtest2Ex"} : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>) -> (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>, !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>)
+! CHECK: %[[VAL_25:.*]] = fir.zero_bits !fir.ptr<!fir.array<?xf32>>
+! CHECK: %[[VAL_26:.*]] = fir.embox %[[VAL_25]](%[[VAL_19]]) : (!fir.ptr<!fir.array<?xf32>>, !fir.shapeshift<1>) -> !fir.box<!fir.ptr<!fir.array<?xf32>>>
+! CHECK: fir.store %[[VAL_26]] to %[[VAL_24]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>
+! CHECK: %[[VAL_27:.*]] = fir.convert %[[VAL_3]]#0 : (!fir.ref<i64>) -> !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_28:.*]] = fir.load %[[VAL_27]] : !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_29:.*]] = fir.convert %[[VAL_24]]#0 : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>) -> !fir.ref<!fir.box<none>>
+! CHECK: %[[VAL_30:.*]] = fir.convert %[[VAL_28]] : (!fir.ptr<i64>) -> !fir.llvm_ptr<i8>
+! CHECK: %[[VAL_31:.*]] = fir.call @_FortranAPointerAssociateScalar(%[[VAL_29]], %[[VAL_30]]) fastmath<contract> : (!fir.ref<!fir.box<none>>, !fir.llvm_ptr<i8>) -> none
+! CHECK: %[[VAL_32:.*]] = fir.load %[[VAL_24]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>
+! CHECK: %[[VAL_33:.*]] = arith.constant 7 : index
+! CHECK: %[[VAL_34:.*]] = hlfir.designate %[[VAL_32]] (%[[VAL_33]]) : (!fir.box<!fir.ptr<!fir.array<?xf32>>>, index) -> !fir.ref<f32>
+! CHECK: %[[VAL_35:.*]] = fir.load %[[VAL_34]] : !fir.ref<f32>
+
+subroutine test3(cp, n)
+ character(len=11) :: c(n:2*n), res
+ pointer (cp, c)
+ res = c(7)
+end subroutine test3
+! CHECK-LABEL: func.func @_QPtest3(
+! CHECK-SAME: %[[VAL_0:.*]]: !fir.ref<i64> {fir.bindc_name = "cp"},
+! CHECK-SAME: %[[VAL_1:.*]]: !fir.ref<i32> {fir.bindc_name = "n"}) {
+! CHECK: %[[VAL_2:.*]] = fir.alloca !fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>
+! CHECK: %[[VAL_3:.*]]:2 = hlfir.declare %[[VAL_1]] {uniq_name = "_QFtest3En"} : (!fir.ref<i32>) -> (!fir.ref<i32>, !fir.ref<i32>)
+! CHECK: %[[VAL_4:.*]]:2 = hlfir.declare %[[VAL_0]] {uniq_name = "_QFtest3Ecp"} : (!fir.ref<i64>) -> (!fir.ref<i64>, !fir.ref<i64>)
+! CHECK: %[[VAL_5:.*]] = arith.constant 11 : index
+! CHECK: %[[VAL_8:.*]] = arith.constant 11 : index
+! CHECK: %[[VAL_24:.*]] = fir.shape_shift %{{.*}}, %{{.*}} : (index, index) -> !fir.shapeshift<1>
+! CHECK: %[[VAL_29:.*]]:2 = hlfir.declare %[[VAL_2]] typeparams %[[VAL_8]] {fortran_attrs = #fir.var_attrs<pointer>, uniq_name = "_QFtest3Ec"} : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>>, index) -> (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>>, !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>>)
+! CHECK: %[[VAL_30:.*]] = fir.zero_bits !fir.ptr<!fir.array<?x!fir.char<1,11>>>
+! CHECK: %[[VAL_31:.*]] = fir.embox %[[VAL_30]](%[[VAL_24]]) : (!fir.ptr<!fir.array<?x!fir.char<1,11>>>, !fir.shapeshift<1>) -> !fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>
+! CHECK: fir.store %[[VAL_31]] to %[[VAL_29]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>>
+! CHECK: %[[VAL_32:.*]] = fir.convert %[[VAL_4]]#0 : (!fir.ref<i64>) -> !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_33:.*]] = fir.load %[[VAL_32]] : !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_34:.*]] = fir.convert %[[VAL_29]]#0 : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>>) -> !fir.ref<!fir.box<none>>
+! CHECK: %[[VAL_35:.*]] = fir.convert %[[VAL_33]] : (!fir.ptr<i64>) -> !fir.llvm_ptr<i8>
+! CHECK: %[[VAL_36:.*]] = fir.call @_FortranAPointerAssociateScalar(%[[VAL_34]], %[[VAL_35]]) fastmath<contract> : (!fir.ref<!fir.box<none>>, !fir.llvm_ptr<i8>) -> none
+! CHECK: %[[VAL_37:.*]] = fir.load %[[VAL_29]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>>
+! CHECK: %[[VAL_38:.*]] = arith.constant 7 : index
+! CHECK: %[[VAL_39:.*]] = hlfir.designate %[[VAL_37]] (%[[VAL_38]]) typeparams %[[VAL_8]] : (!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,11>>>>, index, index) -> !fir.ref<!fir.char<1,11>>
+
+subroutine test4(n)
+ character(len=n) :: c, res
+ pointer (cp, c)
+ res = c
+end subroutine test4
+! CHECK-LABEL: func.func @_QPtest4(
+! CHECK-SAME: %[[VAL_0:.*]]: !fir.ref<i32> {fir.bindc_name = "n"}) {
+! CHECK: %[[VAL_1:.*]] = fir.alloca !fir.box<!fir.ptr<!fir.char<1,?>>>
+! CHECK: %[[VAL_2:.*]]:2 = hlfir.declare %[[VAL_0]] {uniq_name = "_QFtest4En"} : (!fir.ref<i32>) -> (!fir.ref<i32>, !fir.ref<i32>)
+! CHECK: %[[VAL_3:.*]] = fir.alloca i64 {bindc_name = "cp", uniq_name = "_QFtest4Ecp"}
+! CHECK: %[[VAL_4:.*]]:2 = hlfir.declare %[[VAL_3]] {uniq_name = "_QFtest4Ecp"} : (!fir.ref<i64>) -> (!fir.ref<i64>, !fir.ref<i64>)
+! CHECK: %[[VAL_5:.*]] = fir.load %[[VAL_2]]#0 : !fir.ref<i32>
+! CHECK: %[[VAL_6:.*]] = arith.constant 0 : i32
+! CHECK: %[[VAL_7:.*]] = arith.cmpi sgt, %[[VAL_5]], %[[VAL_6]] : i32
+! CHECK: %[[VAL_8:.*]] = arith.select %[[VAL_7]], %[[VAL_5]], %[[VAL_6]] : i32
+! CHECK: %[[VAL_13:.*]]:2 = hlfir.declare %[[VAL_1]] typeparams %[[VAL_8]] {fortran_attrs = #fir.var_attrs<pointer>, uniq_name = "_QFtest4Ec"} : (!fir.ref<!fir.box<!fir.ptr<!fir.char<1,?>>>>, i32) -> (!fir.ref<!fir.box<!fir.ptr<!fir.char<1,?>>>>, !fir.ref<!fir.box<!fir.ptr<!fir.char<1,?>>>>)
+! CHECK: %[[VAL_14:.*]] = fir.zero_bits !fir.ptr<!fir.char<1,?>>
+! CHECK: %[[VAL_15:.*]] = fir.embox %[[VAL_14]] typeparams %[[VAL_8]] : (!fir.ptr<!fir.char<1,?>>, i32) -> !fir.box<!fir.ptr<!fir.char<1,?>>>
+! CHECK: fir.store %[[VAL_15]] to %[[VAL_13]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.char<1,?>>>>
+! CHECK: %[[VAL_22:.*]] = fir.convert %[[VAL_4]]#0 : (!fir.ref<i64>) -> !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_23:.*]] = fir.load %[[VAL_22]] : !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_24:.*]] = fir.convert %[[VAL_13]]#0 : (!fir.ref<!fir.box<!fir.ptr<!fir.char<1,?>>>>) -> !fir.ref<!fir.box<none>>
+! CHECK: %[[VAL_25:.*]] = fir.convert %[[VAL_23]] : (!fir.ptr<i64>) -> !fir.llvm_ptr<i8>
+! CHECK: %[[VAL_26:.*]] = fir.call @_FortranAPointerAssociateScalar(%[[VAL_24]], %[[VAL_25]]) fastmath<contract> : (!fir.ref<!fir.box<none>>, !fir.llvm_ptr<i8>) -> none
+! CHECK: %[[VAL_27:.*]] = fir.load %[[VAL_13]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.char<1,?>>>>
+! CHECK: %[[VAL_28:.*]] = fir.box_addr %[[VAL_27]] : (!fir.box<!fir.ptr<!fir.char<1,?>>>) -> !fir.ptr<!fir.char<1,?>>
+! CHECK: %[[VAL_29:.*]] = fir.emboxchar %[[VAL_28]], %[[VAL_8]] : (!fir.ptr<!fir.char<1,?>>, i32) -> !fir.boxchar<1>
+
+subroutine test5()
+ type t
+ sequence
+ real r
+ integer i
+ end type t
+ type(t) :: v
+ integer res
+ pointer (cp, v(3:11))
+ res = v(7)%i
+end subroutine test5
+! CHECK-LABEL: func.func @_QPtest5() {
+! CHECK: %[[VAL_0:.*]] = fir.alloca !fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>
+! CHECK: %[[VAL_1:.*]] = fir.alloca i64 {bindc_name = "cp", uniq_name = "_QFtest5Ecp"}
+! CHECK: %[[VAL_2:.*]]:2 = hlfir.declare %[[VAL_1]] {uniq_name = "_QFtest5Ecp"} : (!fir.ref<i64>) -> (!fir.ref<i64>, !fir.ref<i64>)
+! CHECK: %[[VAL_5:.*]] = arith.constant 3 : index
+! CHECK: %[[VAL_6:.*]] = arith.constant 9 : index
+! CHECK: %[[VAL_7:.*]] = fir.alloca !fir.array<9x!fir.type<_QFtest5Tt{r:f32,i:i32}>> {bindc_name = "v", uniq_name = "_QFtest5Ev"}
+! CHECK: %[[VAL_8:.*]] = fir.shape_shift %[[VAL_5]], %[[VAL_6]] : (index, index) -> !fir.shapeshift<1>
+! CHECK: %[[VAL_13:.*]]:2 = hlfir.declare %[[VAL_0]] {fortran_attrs = #fir.var_attrs<pointer>, uniq_name = "_QFtest5Ev"} : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>>) -> (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>>, !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>>)
+! CHECK: %[[VAL_14:.*]] = fir.zero_bits !fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>
+! CHECK: %[[VAL_15:.*]] = fir.embox %[[VAL_14]](%[[VAL_8]]) : (!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>, !fir.shapeshift<1>) -> !fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>
+! CHECK: fir.store %[[VAL_15]] to %[[VAL_13]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>>
+! CHECK: %[[VAL_16:.*]] = fir.convert %[[VAL_2]]#0 : (!fir.ref<i64>) -> !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_17:.*]] = fir.load %[[VAL_16]] : !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_18:.*]] = fir.convert %[[VAL_13]]#0 : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>>) -> !fir.ref<!fir.box<none>>
+! CHECK: %[[VAL_19:.*]] = fir.convert %[[VAL_17]] : (!fir.ptr<i64>) -> !fir.llvm_ptr<i8>
+! CHECK: %[[VAL_20:.*]] = fir.call @_FortranAPointerAssociateScalar(%[[VAL_18]], %[[VAL_19]]) fastmath<contract> : (!fir.ref<!fir.box<none>>, !fir.llvm_ptr<i8>) -> none
+! CHECK: %[[VAL_21:.*]] = fir.load %[[VAL_13]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>>
+! CHECK: %[[VAL_22:.*]] = arith.constant 7 : index
+! CHECK: %[[VAL_23:.*]] = hlfir.designate %[[VAL_21]] (%[[VAL_22]]) : (!fir.box<!fir.ptr<!fir.array<?x!fir.type<_QFtest5Tt{r:f32,i:i32}>>>>, index) -> !fir.ref<!fir.type<_QFtest5Tt{r:f32,i:i32}>>
+! CHECK: %[[VAL_24:.*]] = hlfir.designate %[[VAL_23]]{"i"} : (!fir.ref<!fir.type<_QFtest5Tt{r:f32,i:i32}>>) -> !fir.ref<i32>
+! CHECK: %[[VAL_25:.*]] = fir.load %[[VAL_24]] : !fir.ref<i32>
+
+subroutine test6(n)
+ character(len=n) :: c(20), res1
+ real x, res2
+ pointer (cp, c)
+ pointer (cp, x(n:17))
+ res1 = c(9)
+ res2 = x(5)
+end subroutine test6
+! CHECK-LABEL: func.func @_QPtest6(
+! CHECK-SAME: %[[VAL_0:.*]]: !fir.ref<i32> {fir.bindc_name = "n"}) {
+! CHECK: %[[VAL_1:.*]] = fir.alloca !fir.box<!fir.ptr<!fir.array<?xf32>>>
+! CHECK: %[[VAL_2:.*]] = fir.alloca !fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>
+! CHECK: %[[VAL_3:.*]]:2 = hlfir.declare %[[VAL_0]] {uniq_name = "_QFtest6En"} : (!fir.ref<i32>) -> (!fir.ref<i32>, !fir.ref<i32>)
+! CHECK: %[[VAL_4:.*]] = fir.alloca i64 {bindc_name = "cp", uniq_name = "_QFtest6Ecp"}
+! CHECK: %[[VAL_5:.*]]:2 = hlfir.declare %[[VAL_4]] {uniq_name = "_QFtest6Ecp"} : (!fir.ref<i64>) -> (!fir.ref<i64>, !fir.ref<i64>)
+! CHECK: %[[VAL_8:.*]] = fir.load %[[VAL_3]]#0 : !fir.ref<i32>
+! CHECK: %[[VAL_9:.*]] = arith.constant 0 : i32
+! CHECK: %[[VAL_10:.*]] = arith.cmpi sgt, %[[VAL_8]], %[[VAL_9]] : i32
+! CHECK: %[[VAL_11:.*]] = arith.select %[[VAL_10]], %[[VAL_8]], %[[VAL_9]] : i32
+! CHECK: %[[VAL_12:.*]] = arith.constant 20 : index
+
+! CHECK: %[[VAL_14:.*]] = fir.shape %[[VAL_12]] : (index) -> !fir.shape<1>
+! CHECK: %[[VAL_20:.*]]:2 = hlfir.declare %[[VAL_2]] typeparams %[[VAL_11]] {fortran_attrs = #fir.var_attrs<pointer>, uniq_name = "_QFtest6Ec"} : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>>, i32) -> (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>>, !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>>)
+! CHECK: %[[VAL_21:.*]] = fir.zero_bits !fir.ptr<!fir.array<?x!fir.char<1,?>>>
+! CHECK: %[[VAL_22:.*]] = fir.embox %[[VAL_21]](%[[VAL_14]]) typeparams %[[VAL_11]] : (!fir.ptr<!fir.array<?x!fir.char<1,?>>>, !fir.shape<1>, i32) -> !fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>
+! CHECK: fir.store %[[VAL_22]] to %[[VAL_20]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>>
+
+! CHECK: %[[VAL_41:.*]] = fir.shape_shift %{{.*}}, %{{.*}} : (index, index) -> !fir.shapeshift<1>
+! CHECK: %[[VAL_46:.*]]:2 = hlfir.declare %[[VAL_1]] {fortran_attrs = #fir.var_attrs<pointer>, uniq_name = "_QFtest6Ex"} : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>) -> (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>, !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>)
+! CHECK: %[[VAL_47:.*]] = fir.zero_bits !fir.ptr<!fir.array<?xf32>>
+! CHECK: %[[VAL_48:.*]] = fir.embox %[[VAL_47]](%[[VAL_41]]) : (!fir.ptr<!fir.array<?xf32>>, !fir.shapeshift<1>) -> !fir.box<!fir.ptr<!fir.array<?xf32>>>
+! CHECK: fir.store %[[VAL_48]] to %[[VAL_46]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>
+
+! CHECK: %[[VAL_49:.*]] = fir.convert %[[VAL_5]]#0 : (!fir.ref<i64>) -> !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_50:.*]] = fir.load %[[VAL_49]] : !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_51:.*]] = fir.convert %[[VAL_20]]#0 : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>>) -> !fir.ref<!fir.box<none>>
+! CHECK: %[[VAL_52:.*]] = fir.convert %[[VAL_50]] : (!fir.ptr<i64>) -> !fir.llvm_ptr<i8>
+! CHECK: %[[VAL_53:.*]] = fir.call @_FortranAPointerAssociateScalar(%[[VAL_51]], %[[VAL_52]]) fastmath<contract> : (!fir.ref<!fir.box<none>>, !fir.llvm_ptr<i8>) -> none
+! CHECK: %[[VAL_54:.*]] = fir.load %[[VAL_20]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>>
+! CHECK: %[[VAL_55:.*]] = arith.constant 9 : index
+! CHECK: %[[VAL_56:.*]] = hlfir.designate %[[VAL_54]] (%[[VAL_55]]) typeparams %[[VAL_11]] : (!fir.box<!fir.ptr<!fir.array<?x!fir.char<1,?>>>>, index, i32) -> !fir.boxchar<1>
+
+! CHECK: %[[VAL_57:.*]] = fir.convert %[[VAL_5]]#0 : (!fir.ref<i64>) -> !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_58:.*]] = fir.load %[[VAL_57]] : !fir.ref<!fir.ptr<i64>>
+! CHECK: %[[VAL_59:.*]] = fir.convert %[[VAL_46]]#0 : (!fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>) -> !fir.ref<!fir.box<none>>
+! CHECK: %[[VAL_60:.*]] = fir.convert %[[VAL_58]] : (!fir.ptr<i64>) -> !fir.llvm_ptr<i8>
+! CHECK: %[[VAL_61:.*]] = fir.call @_FortranAPointerAssociateScalar(%[[VAL_59]], %[[VAL_60]]) fastmath<contract> : (!fir.ref<!fir.box<none>>, !fir.llvm_ptr<i8>) -> none
+! CHECK: %[[VAL_62:.*]] = fir.load %[[VAL_46]]#0 : !fir.ref<!fir.box<!fir.ptr<!fir.array<?xf32>>>>
+! CHECK: %[[VAL_63:.*]] = arith.constant 5 : index
+! CHECK: %[[VAL_64:.*]] = hlfir.designate %[[VAL_62]] (%[[VAL_63]]) : (!fir.box<!fir.ptr<!fir.array<?xf32>>>, index) -> !fir.ref<f32>
+! CHECK: %[[VAL_65:.*]] = fir.load %[[VAL_64]] : !fir.ref<f32>