Rewire the dumping on cling::Value to its new implementation.

Dump cling::Value within setNoAlloc routines because this is its lifespan,
otherwise gets deleted if nobody requested it. I.e it was created only for
value printing purposes.

Dump cling::Value outside setWithAlloc because the actual value is not put inside
until the call to ::new finishes, thus we need to do it outside, i.e in EvaluateInternal.

Switch on the ValueExtraction synthesizer even when 'just' value printing. We
depend on it. Must be factored out properly in one class.

Stop attaching the value printing template magic, which didn't work in some cases.

Update the ref file, because now there is better type information.

Adapt the user-defined printout functions (TDatime).
This commit is contained in:
Vassil Vassilev 2014-05-16 17:40:27 +02:00 committed by sftnight
parent 245f098fe1
commit c86fbc27b9
11 changed files with 239 additions and 172 deletions

View File

@ -12,8 +12,6 @@
#ifdef __cplusplus
extern "C"
#endif
void cling_PrintValue(void* /*clang::Expr**/ E,
void* /*clang::ASTContext**/ C,
const void* value);
void cling_PrintValue(void* /*cling::Value**/ V);
#endif // CLING_VALUEPRINTERC_H

View File

@ -10,7 +10,7 @@
#ifndef CLING_VALUEPRINTER_H
#define CLING_VALUEPRINTER_H
#include "cling/Interpreter/ValuePrinterInfo.h"
#include "cling/Interpreter/Value.h"
#include <string>
namespace llvm {
@ -26,11 +26,11 @@ namespace cling {
///\code
/// template <typename POSSIBLYDERIVED>
/// std::string printValue(const MyClass* const p, POSSIBLYDERIVED* ac,
/// const ValuePrinterInfo& VPI);
/// const Value& V);
///\endcode
template <typename TY>
std::string printValue(const void* const p, TY* const u,
const ValuePrinterInfo& VPI);
//template <typename TY>
//std::string printValue(const void* const p, TY* const u,
// const Value& V);
///\brief Generic interface to type printing.
///
@ -38,34 +38,29 @@ namespace cling {
///\code
/// template <typename POSSIBLYDERIVED>
/// std::string printType(const MyClass* const p, POSSIBLYDERIVED* ac,
/// const ValuePrinterInfo& VPI);
/// const Value& V);
///\endcode
template <typename TY>
std::string printType(const void* const p, TY* const u,
const ValuePrinterInfo& VPI);
//template <typename TY>
//std::string printType(const void* const p, TY* const u,
// const Value& V);
namespace valuePrinterInternal {
std::string printValue_Default(const void* const p,
const ValuePrinterInfo& PVI);
std::string printType_Default(const ValuePrinterInfo& PVI);
std::string printValue_Default(const Value& V);
std::string printType_Default(const Value& V);
void StreamClingValue(llvm::raw_ostream& o, const Value* VR,
clang::ASTContext& C);
void StreamClingValue(llvm::raw_ostream& o, const Value* VR);
void flushToStream(llvm::raw_ostream& o, const std::string& s);
template <typename T>
T& Select(llvm::raw_ostream* o, Interpreter* I,
clang::ASTContext* C, T& value) {
ValuePrinterInfo VPI(I, C);
template<typename T>
void Select(llvm::raw_ostream* o, const Value* value) {
// Only because we don't want to include llvm::raw_ostream in the header
flushToStream(*o, printType(&value, &value, VPI)
+ printValue(&value, &value, VPI) + '\n');
return value;
//flushToStream(*o, printType(0, (void*)0, value)
// + printValue(0, (void*)0, value) + '\n');
}
template <typename T>
/* template <typename T>
const T& Select(llvm::raw_ostream* o, Interpreter* I,
clang::ASTContext* C, const T& value) {
ValuePrinterInfo VPI(I, C);
@ -84,21 +79,10 @@ namespace cling {
+ printValue((const void*) value, value, VPI) + '\n');
return value;
}
*/
} // namespace valuePrinterInternal
///\brief Catch-all implementation for value printing.
template <typename TY>
std::string printValue(const void* const p, TY* const /*u*/,
const ValuePrinterInfo& PVI) {
return valuePrinterInternal::printValue_Default(p, PVI);
}
///\brief Catch-all implementation for type printing.
template <typename TY>
std::string printType(const void* const p, TY* const /*u*/,
const ValuePrinterInfo& PVI) {
return valuePrinterInternal::printType_Default(PVI);
}
}

View File

@ -470,7 +470,6 @@ namespace cling {
CO.ResultEvaluation = (bool)V;
CO.DynamicScoping = isDynamicLookupEnabled();
CO.Debug = isPrintingDebug();
if (EvaluateInternal(input, CO, V, T) == Interpreter::kFailure) {
return Interpreter::kFailure;
}
@ -946,10 +945,21 @@ namespace cling {
|| lastT->getState() == Transaction::kRolledBack)
&& "Not committed?");
if (lastT->getIssuedDiags() != Transaction::kErrors) {
Value resultV;
if (!V)
V = &resultV;
if (!lastT->getWrapperFD()) // no wrapper to run
return Interpreter::kSuccess;
else if (RunFunction(lastT->getWrapperFD(), V) < kExeFirstError)
else if (RunFunction(lastT->getWrapperFD(), V) < kExeFirstError){
if (lastT->getCompilationOpts().ValuePrinting
!= CompilationOptions::VPDisabled
&& V->isValid()
// the !V->needsManagedAllocation() case is handled by
// dumpIfNoStorage.
&& V->needsManagedAllocation())
V->dump();
return Interpreter::kSuccess;
}
}
if (V)
*V = Value();

View File

@ -8,12 +8,12 @@
//------------------------------------------------------------------------------
#include "cling/Interpreter/Interpreter.h"
#include "cling/Interpreter/CValuePrinter.h"
//#include "cling/Interpreter/CValuePrinter.h"
#include "cling/Interpreter/DynamicExprInfo.h"
#include "cling/Interpreter/InterpreterCallbacks.h"
#include "cling/Interpreter/LookupHelper.h"
#include "cling/Interpreter/ValuePrinter.h"
#include "cling/Interpreter/ValuePrinterInfo.h"
//#include "cling/Interpreter/ValuePrinter.h"
//#include "cling/Interpreter/ValuePrinterInfo.h"
#include "clang/AST/Type.h"
@ -24,10 +24,10 @@ namespace internal {
void symbol_requester() {
const char* const argv[] = {"libcling__symbol_requester", 0};
Interpreter I(1, argv);
ValuePrinterInfo VPI(0, 0); // asserts, but we don't call.
valuePrinterInternal::printValue_Default(0, VPI);
cling_PrintValue(0, 0, 0);
valuePrinterInternal::flushToStream(llvm::outs(), "");
//Value V; // asserts, but we don't call.
//valuePrinterInternal::printValue_Default(0, V);
//cling_PrintValue(0);
//valuePrinterInternal::flushToStream(llvm::outs(), "");
LookupHelper h(0,0);
h.findType("", LookupHelper::NoDiagnostics);
h.findScope("", LookupHelper::NoDiagnostics);

View File

@ -54,7 +54,9 @@ namespace cling {
}
void ValueExtractionSynthesizer::Transform() {
if (!getTransaction()->getCompilationOpts().ResultEvaluation)
const CompilationOptions& CO = getTransaction()->getCompilationOpts();
// If we do not evaluate the result, or printing out the result return.
if (!(CO.ResultEvaluation || CO.ValuePrinting))
return;
FunctionDecl* FD = getTransaction()->getWrapperFD();
@ -368,6 +370,26 @@ namespace cling {
// Provide implementation of the functions that ValueExtractionSynthesizer calls
namespace {
static void dumpIfNoStorage(void* vpI, void* vpV) {
cling::Interpreter* I = (cling::Interpreter*)vpI;
const cling::Value& V = *(cling::Value*)vpV;
//const cling::Transaction& T = *(cling::Transaction*)vpT);
// If the value copies over the temporary we must delay the printing until
// the temporary gets copied over. For the rest of the temporaries we *must*
// dump here because their lifetime will be gone otherwise. Eg.
//
// std::string f(); f().c_str() // have to dump during the same stmt.
//
assert(!V.needsManagedAllocation() && "Must contain non managed temporary");
// FIXME: We should pass in the 'right' transaction when we requested the
// code. This should happen with extra parameter.
const cling::CompilationOptions& CO
= I->getLastTransaction()->getCompilationOpts();
if (CO.ValuePrinting != cling::CompilationOptions::VPDisabled)
V.dump();
}
///\brief Allocate the Value and return the Value
/// for an expression evaluated at the prompt.
///
@ -390,26 +412,32 @@ namespace runtime {
void setValueNoAlloc(void* vpI, void* vpSVR, void* vpQT) {
// In cases of void we 'just' need to change the type of the value.
allocateStoredRefValueAndGetGV(vpI, vpSVR, vpQT);
dumpIfNoStorage(vpI, vpSVR);
}
void setValueNoAlloc(void* vpI, void* vpSVR, void* vpQT, float value) {
allocateStoredRefValueAndGetGV(vpI, vpSVR, vpQT).getAs<float>() = value;
dumpIfNoStorage(vpI, vpSVR);
}
void setValueNoAlloc(void* vpI, void* vpSVR, void* vpQT, double value) {
allocateStoredRefValueAndGetGV(vpI, vpSVR, vpQT).getAs<double>() = value;
dumpIfNoStorage(vpI, vpSVR);
}
void setValueNoAlloc(void* vpI, void* vpSVR, void* vpQT,
long double value) {
allocateStoredRefValueAndGetGV(vpI, vpSVR, vpQT).getAs<long double>()
= value;
dumpIfNoStorage(vpI, vpSVR);
}
void setValueNoAlloc(void* vpI, void* vpSVR, void* vpQT,
unsigned long long value) {
allocateStoredRefValueAndGetGV(vpI, vpSVR, vpQT)
.getAs<unsigned long long>() = value;
dumpIfNoStorage(vpI, vpSVR);
}
void setValueNoAlloc(void* vpI, void* vpSVR, void* vpQT, const void* value){
allocateStoredRefValueAndGetGV(vpI, vpSVR, vpQT).getAs<void*>()
= const_cast<void*>(value);
dumpIfNoStorage(vpI, vpSVR);
}
void* setValueWithAlloc(void* vpI, void* vpSVR, void* vpQT) {
return allocateStoredRefValueAndGetGV(vpI, vpSVR, vpQT).getAs<void*>();

View File

@ -10,8 +10,11 @@
#include "cling/Interpreter/ValuePrinter.h"
#include "cling/Interpreter/CValuePrinter.h"
#include "cling/Interpreter/Interpreter.h"
#include "cling/Interpreter/Transaction.h"
#include "cling/Interpreter/ValuePrinterInfo.h"
#include "cling/Interpreter/Value.h"
#include "cling/Utils/AST.h"
#include "clang/AST/ASTContext.h"
#include "clang/AST/Decl.h"
@ -46,25 +49,22 @@
using namespace cling;
// Implements the CValuePrinter interface.
extern "C" void cling_PrintValue(void* /*clang::Expr**/ E,
void* /*clang::ASTContext**/ C,
const void* value) {
clang::Expr* Exp = (clang::Expr*)E;
clang::ASTContext* Context = (clang::ASTContext*)C;
ValuePrinterInfo VPI(Exp->getType(), Context);
extern "C" void cling_PrintValue(void* /*cling::Value**/ V) {
Value* value = (Value*)V;
// We need stream that doesn't close its file descriptor, thus we are not
// using llvm::outs. Keeping file descriptor open we will be able to use
// the results in pipes (Savannah #99234).
llvm::raw_fd_ostream outs (STDOUT_FILENO, /*ShouldClose*/false);
valuePrinterInternal::flushToStream(outs, printType(value, value, VPI)
+ printValue(value, value, VPI));
//std::string typeStr = printType(value->getPtr(), value->getPtr(), *value);
//std::string valueStr = printValue(value->getPtr(), value->getPtr(), *value);
//valuePrinterInternal::flushToStream(outs, typeStr + valueStr);
}
static void StreamValue(llvm::raw_ostream& o, const void* const p,
const ValuePrinterInfo& VPI);
static void StreamValue(llvm::raw_ostream& o, const void* V, clang::QualType QT,
clang::ASTContext& C);
static void StreamChar(llvm::raw_ostream& o, const char v) {
if (isprint(v))
@ -89,26 +89,22 @@ static void StreamCharPtr(llvm::raw_ostream& o, const char* const v) {
else o << "\"";
}
static void StreamRef(llvm::raw_ostream& o, const void* v,
const ValuePrinterInfo& VPI) {
const clang::ReferenceType* RTy
= llvm::dyn_cast<clang::ReferenceType>(VPI.getType().getTypePtr());
ValuePrinterInfo VPIRefed(RTy->getPointeeType(), VPI.getASTContext());
StreamValue(o, v, VPIRefed);
static void StreamRef(llvm::raw_ostream& o, const void** V, clang::QualType Ty,
clang::ASTContext& C){
const clang::ReferenceType* RTy = llvm::dyn_cast<clang::ReferenceType>(Ty);
StreamValue(o, *V, RTy->getPointeeTypeAsWritten(), C);
}
static void StreamPtr(llvm::raw_ostream& o, const void* v) {
o << v;
}
static void StreamArr(llvm::raw_ostream& o, const void* p,
const ValuePrinterInfo& VPI) {
const clang::QualType& Ty = VPI.getType();
clang::ASTContext& C = *VPI.getASTContext();
static void StreamArr(llvm::raw_ostream& o, const void* V, clang::QualType Ty,
clang::ASTContext& C) {
const clang::ArrayType* ArrTy = Ty->getAsArrayTypeUnsafe();
clang::QualType ElementTy = ArrTy->getElementType();
if (ElementTy->isCharType())
StreamCharPtr(o, (const char*)p);
StreamCharPtr(o, (const char*)V);
else if (Ty->isConstantArrayType()) {
// Stream a constant array by streaming up to 5 elements.
const clang::ConstantArrayType* CArrTy
@ -117,9 +113,8 @@ static void StreamArr(llvm::raw_ostream& o, const void* p,
size_t ElBytes = C.getTypeSize(ElementTy) / C.getCharWidth();
size_t Size = (size_t)APSize.getZExtValue();
o << "{ ";
ValuePrinterInfo ElVPI(ElementTy, &C);
for (size_t i = 0; i < Size; ++i) {
StreamValue(o, ((const char*)p) + i * ElBytes, ElVPI);
StreamValue(o, (const char*) V + i * ElBytes, ElementTy, C);
if (i + 1 < Size) {
if (i == 4) {
o << "...";
@ -130,15 +125,21 @@ static void StreamArr(llvm::raw_ostream& o, const void* p,
}
o << " }";
} else
StreamPtr(o, p);
StreamPtr(o, V);
}
static void StreamFunction(llvm::raw_ostream& o, const void* addr,
ValuePrinterInfo VPI) {
o << "Function @" << addr << '\n';
static void StreamFunction(llvm::raw_ostream& o, Value* V) {
o << "Function @" << V->getPtr() << '\n';
Interpreter* interp = V->getInterpreter();
const Transaction* T = interp->getLastTransaction();
assert(T->getWrapperFD() && "Must have a wrapper.");
clang::FunctionDecl* WrapperFD = T->getWrapperFD();
clang::Expr* ExprAttachedTo
= utils::Analyze::GetOrCreateLastExpr(WrapperFD, /*foundAtPos*/0,
/*omitDS*/false, &interp->getSema());
const clang::DeclRefExpr* DeclRefExp
= llvm::dyn_cast_or_null<clang::DeclRefExpr>(VPI.tryGetValuePrintedExpr());
= llvm::dyn_cast_or_null<clang::DeclRefExpr>(ExprAttachedTo);
const clang::FunctionDecl* FD = 0;
if (DeclRefExp)
FD = llvm::dyn_cast_or_null<clang::FunctionDecl>(DeclRefExp->getDecl());
@ -148,7 +149,7 @@ static void StreamFunction(llvm::raw_ostream& o, const void* addr,
const char* cEnd = 0;
bool Invalid;
if (SRange.isValid()) {
clang::SourceManager& SM = VPI.getASTContext()->getSourceManager();
clang::SourceManager& SM = V->getASTContext().getSourceManager();
clang::SourceLocation LocBegin = SRange.getBegin();
LocBegin = SM.getExpansionRange(LocBegin).first;
o << " at " << SM.getFilename(LocBegin);
@ -181,7 +182,7 @@ static void StreamFunction(llvm::raw_ostream& o, const void* addr,
} else {
o << ":\n";
// type-based printing:
VPI.getType().print(o, VPI.getASTContext()->getPrintingPolicy());
V->getType().print(o, V->getASTContext().getPrintingPolicy());
}
// type-based print() never and decl-based print() sometimes does not include
// a final newline:
@ -191,87 +192,77 @@ static void StreamFunction(llvm::raw_ostream& o, const void* addr,
static void StreamLongDouble(llvm::raw_ostream& o, const Value* value,
clang::ASTContext& C) {
std::stringstream sstr;
sstr << value->getAs<long double>();
sstr << value->simplisticCastAs<long double>();
o << sstr.str() << 'L';
}
static void StreamObj(llvm::raw_ostream& o, const void* v,
const ValuePrinterInfo& VPI) {
const clang::Type* Ty = VPI.getType().getTypePtr();
static void StreamObj(llvm::raw_ostream& o, const void* V, clang::QualType Ty) {
if (clang::CXXRecordDecl* CXXRD = Ty->getAsCXXRecordDecl()) {
std::string QualName = CXXRD->getQualifiedNameAsString();
if (QualName == "cling::Value"){
valuePrinterInternal::StreamClingValue(o, (const Value*)v,
*VPI.getASTContext());
return;
} else if (QualName == "cling::Value") {
valuePrinterInternal::StreamClingValue(o, (const Value*)v,
*VPI.getASTContext());
valuePrinterInternal::StreamClingValue(o, (const cling::Value*)V);
return;
}
} // if CXXRecordDecl
// TODO: Print the object members.
o << "@" << v;
o << "@" << V;
}
static void StreamValue(llvm::raw_ostream& o, const void* const p,
const ValuePrinterInfo& VPI) {
clang::ASTContext& C = *VPI.getASTContext();
clang::QualType Ty = VPI.getType().getDesugaredType(C);
static void StreamValue(llvm::raw_ostream& o, const void* V,
clang::QualType Ty, clang::ASTContext& C) {
if (const clang::BuiltinType *BT
= llvm::dyn_cast<clang::BuiltinType>(Ty.getCanonicalType())) {
switch (BT->getKind()) {
case clang::BuiltinType::Bool:
if (*(const bool*)p) o << "true";
else o << "false"; break;
case clang::BuiltinType::Char_U:
case clang::BuiltinType::UChar:
case clang::BuiltinType::Char_S:
case clang::BuiltinType::SChar: StreamChar(o, *(const char*)p); break;
case clang::BuiltinType::Short: o << *(const short*)p; break;
if (*(const bool*)V)
o << "true";
else
o << "false";
break;
case clang::BuiltinType::Char_U: // intentional fall through
case clang::BuiltinType::UChar: // intentional fall through
case clang::BuiltinType::Char_S: // intentional fall through
case clang::BuiltinType::SChar:
StreamChar(o, *(const char*)V); break;
case clang::BuiltinType::Short:
o << *(const short*)V; break;
case clang::BuiltinType::UShort:
o << *(const unsigned short*)p;
break;
case clang::BuiltinType::Int: o << *(const int*)p; break;
o << *(const unsigned short*)V; break;
case clang::BuiltinType::Int:
o << *(const int*)V; break;
case clang::BuiltinType::UInt:
o << *(const unsigned int*)p;
break;
case clang::BuiltinType::Long: o << *(const long*)p; break;
o << *(const unsigned int*)V; break;
case clang::BuiltinType::Long:
o << *(const long*)V; break;
case clang::BuiltinType::ULong:
o << *(const unsigned long*)p;
break;
o << *(const unsigned long*)V; break;
case clang::BuiltinType::LongLong:
o << *(const long long*)p;
break;
o << *(const long long*)V; break;
case clang::BuiltinType::ULongLong:
o << *(const unsigned long long*)p;
break;
case clang::BuiltinType::Float: o << *(const float*)p; break;
case clang::BuiltinType::Double: o << *(const double*)p; break;
o << *(const unsigned long long*)V; break;
case clang::BuiltinType::Float:
o << *(const float*)V; break;
case clang::BuiltinType::Double:
o << *(const double*)V; break;
case clang::BuiltinType::LongDouble: {
std::stringstream ssLD;
ssLD << *(const long double*)p;
ssLD << *(const long double*)V;
o << ssLD.str() << 'L'; break;
}
default:
StreamObj(o, p, ValuePrinterInfo(Ty, &C));
StreamObj(o, V, Ty);
}
}
else if (Ty.getAsString().compare("class std::basic_string<char>") == 0
|| Ty.getAsString().compare("class std::__1::basic_string<char, "
"struct std::__1::char_traits<char>, "
"class std::__1::allocator<char> >") == 0
|| Ty.getAsString().compare("class std::__1::basic_string<char>")
== 0) {
StreamObj(o, p, ValuePrinterInfo(Ty, &C));
else if (Ty.getAsString().compare("std::string") == 0) {
StreamObj(o, V, Ty);
o << " "; // force a space
o <<"c_str: ";
StreamCharPtr(o, ((const char*) (*(const std::string*)p).c_str()));
StreamCharPtr(o, ((const char*) (*(const std::string*)V).c_str()));
}
else if (Ty->isEnumeralType()) {
clang::EnumDecl* ED = Ty->getAs<clang::EnumType>()->getDecl();
uint64_t value = *(const uint64_t*)p;
uint64_t value = *(const uint64_t*)V;
bool IsFirst = true;
llvm::APSInt ValAsAPSInt = C.MakeIntValue(value, Ty);
for (clang::EnumDecl::enumerator_iterator I = ED->enumerator_begin(),
@ -287,69 +278,125 @@ static void StreamValue(llvm::raw_ostream& o, const void* const p,
o << " : (int) " << ValAsAPSInt.toString(/*Radix = */10);
}
else if (Ty->isReferenceType())
StreamRef(o, p, VPI);
StreamRef(o, (const void**)&V, Ty, C);
else if (Ty->isPointerType()) {
clang::QualType PointeeTy = Ty->getPointeeType();
if (PointeeTy->isCharType())
StreamCharPtr(o, (const char*)p);
StreamCharPtr(o, (const char*)V);
else
StreamPtr(o, p);
StreamPtr(o, V);
}
else if (Ty->isArrayType())
StreamArr(o, p, ValuePrinterInfo(Ty, &C));
StreamArr(o, V, Ty, C);
else if (Ty->isFunctionType())
StreamFunction(o, p, VPI);
StreamFunction(o, const_cast<cling::Value*>((const cling::Value*)V));
else
StreamObj(o, p, ValuePrinterInfo(Ty, &C));
StreamObj(o, V, Ty);
}
namespace cling {
namespace valuePrinterInternal {
std::string printValue_Default(const void* const p,
const ValuePrinterInfo& VPI) {
std::string printValue_Default(const Value& V) {
std::string buf;
{
llvm::raw_string_ostream o(buf);
StreamValue(o, p, VPI);
clang::ASTContext& C = V.getASTContext();
clang::QualType Ty = V.getType().getDesugaredType(C);
if (const clang::BuiltinType *BT
= llvm::dyn_cast<clang::BuiltinType>(Ty.getCanonicalType())) {
switch (BT->getKind()) {
case clang::BuiltinType::Bool: // intentional fall through
case clang::BuiltinType::Char_U: // intentional fall through
case clang::BuiltinType::Char_S: // intentional fall through
case clang::BuiltinType::SChar: // intentional fall through
case clang::BuiltinType::Short: // intentional fall through
case clang::BuiltinType::Int: // intentional fall through
case clang::BuiltinType::Long: // intentional fall through
case clang::BuiltinType::LongLong: {
long long res = V.getLL();
StreamValue(o, (const void*)&res, Ty, C);
}
break;
case clang::BuiltinType::UChar: // intentional fall through
case clang::BuiltinType::UShort: // intentional fall through
case clang::BuiltinType::UInt: // intentional fall through
case clang::BuiltinType::ULong: // intentional fall through
case clang::BuiltinType::ULongLong: {
unsigned long long res = V.getULL();
StreamValue(o, (const void*)&res, Ty, C);
}
break;
case clang::BuiltinType::Float: {
float res = V.getFloat();
StreamValue(o, (const void*)&res, Ty, C);
}
break;
case clang::BuiltinType::Double: {
double res = V.getDouble();
StreamValue(o, (const void*)&res, Ty, C);
}
break;
case clang::BuiltinType::LongDouble: {
long double res = V.getLongDouble();
StreamValue(o, (const void*)&res, Ty, C);
}
break;
default:
StreamValue(o, V.getPtr(), Ty, C);
break;
}
}
else if (Ty->isIntegralOrEnumerationType()) {
long long res = V.getLL();
StreamValue(o, &res, Ty, C);
}
else if (Ty->isFunctionType())
StreamValue(o, &V, Ty, C);
else
StreamValue(o, V.getPtr(), Ty, C);
}
return buf;
}
std::string printType_Default(const ValuePrinterInfo& VPI) {
std::string printType_Default(const Value& V) {
std::string buf;
{
llvm::raw_string_ostream o(buf);
o << "(";
o << VPI.getType().getAsString();
o << V.getType().getAsString();
o << ") ";
}
return buf;
}
void StreamClingValue(llvm::raw_ostream& o, const Value* value,
clang::ASTContext& C) {
void StreamClingValue(llvm::raw_ostream& o, const Value* value) {
if (!value || !value->isValid()) {
o << "<<<invalid>>> @" << value;
} else {
clang::ASTContext& C = value->getASTContext();
clang::QualType QT = value->getType();
o << "boxes [";
o << "("
<< QT.getAsString(C.getPrintingPolicy())
<< ") ";
clang::QualType valType = QT.getDesugaredType(C);
clang::QualType valType = QT.getDesugaredType(C).getNonReferenceType();
if (C.hasSameType(valType, C.LongDoubleTy))
StreamLongDouble(o, value, C);
else if (valType->isFloatingType())
o << value->simplisticCastAs<double>();
else if (valType->isIntegerType()) {
if (valType->hasSignedIntegerRepresentation())
o << value->getAs<long long>();
o << value->simplisticCastAs<long long>();
else
o << value->getAs<unsigned long long>();
o << value->simplisticCastAs<unsigned long long>();
} else if (valType->isBooleanType())
o << (value->getAs<unsigned long long>() ? "true" : "false");
else
StreamValue(o, value->getAs<void*>(), ValuePrinterInfo(valType, &C));
o << (value->simplisticCastAs<bool>() ? "true" : "false");
else {
StreamValue(o, value->getPtr(), valType, value->getASTContext());
}
o << "]";
}
}

View File

@ -99,7 +99,7 @@ namespace cling {
Expr* Result = 0;
if (m_Sema->getLangOpts().CPlusPlus)
Result = SynthesizeCppVP(To);
;//Result = SynthesizeCppVP(To);
else
Result = SynthesizeVP(To);

View File

@ -17,4 +17,4 @@ cling::Value V;
gCling->echo("2;", &V);
V
// CHECK-NEXT: 2
// CHECK-NEXT: (cling::Value) boxes [(const int) 2]
// CHECK-NEXT: (cling::Value &) boxes [(int) 2]

View File

@ -12,48 +12,48 @@
#include "cling/Interpreter/Value.h"
cling::Value V;
V // CHECK: (cling::Value) <<<invalid>>> @0x{{.*}}
V // CHECK: (cling::Value &) <<<invalid>>> @0x{{.*}}
gCling->evaluate("return 1;", V);
V // CHECK: (cling::Value) boxes [(int) 1]
V // CHECK: (cling::Value &) boxes [(int) 1]
gCling->evaluate("(void)V", V);
V // CHECK-NEXT: (cling::Value) boxes [(void) @0x{{.*}}]
V // CHECK-NEXT: (cling::Value &) boxes [(void) @0x{{.*}}]
// Returns must put the result in the Value.
bool cond = true;
gCling->evaluate("if (cond) return \"true\"; else return 0;", V);
V // CHECK-NEXT: (cling::Value) boxes [(const char [5]) "true"]
V // CHECK-NEXT: (cling::Value &) boxes [(const char [5]) "true"]
gCling->evaluate("if (cond) return; else return 12;", V);
V // CHECK-NEXT: (cling::Value) boxes [(void) @0x{{.*}}]
V // CHECK-NEXT: (cling::Value &) boxes [(void) @0x{{.*}}]
gCling->evaluate("if (cond) return; int aa = 12;", V);
V // CHECK-NEXT: (cling::Value) boxes [(void) @0x{{.*}}]
V // CHECK-NEXT: (cling::Value &) boxes [(void) @0x{{.*}}]
gCling->evaluate("cond = false; if (cond) return \"true\"; else return 0;", V);
V // CHECK-NEXT: (cling::Value) boxes [(int) 0]
V // CHECK-NEXT: (cling::Value &) boxes [(int) 0]
gCling->evaluate("auto a = 12.3; a;", V);
V // CHECK: (cling::Value) boxes [(double) 1.230000e+01]
V // CHECK: (cling::Value &) boxes [(double) 1.230000e+01]
long LongV = 17;
gCling->evaluate("LongV;", V);
V // CHECK: (cling::Value) boxes [(long) 17]
V // CHECK: (cling::Value &) boxes [(long) 17]
int* IntP = (int*)0x12;
gCling->evaluate("IntP;", V);
V // CHECK: (cling::Value) boxes [(int *) 0x12]
V // CHECK: (cling::Value &) boxes [(int *) 0x12]
cling::Value Result;
gCling->evaluate("V", Result);
// Here we check what happens for record type like cling::Value; they are returned by reference.
Result // CHECK: (cling::Value) boxes [(cling::Value &) boxes [(int *) 0x12]]
V // CHECK: (cling::Value) boxes [(int *) 0x12]
Result // CHECK: (cling::Value &) boxes [(cling::Value &) boxes [(int *) 0x12]]
V // CHECK: (cling::Value &) boxes [(int *) 0x12]
// Savannah #96277
gCling->evaluate("gCling->declare(\"double sin(double);\"); double one = sin(3.141/2);", V);
V // CHECK: (cling::Value) boxes [(double) 1.000000e+00]
V // CHECK: (cling::Value &) boxes [(double) 1.000000e+00]
gCling->process("double one = sin(3.141/2);", &V);
V // CHECK: (cling::Value) boxes [(double) 1.000000e+00]
V // CHECK: (cling::Value &) boxes [(double) 1.000000e+00]
one // CHECK: (double) 1.000
int one; // expected-error {{redefinition of 'one' with a different type: 'int' vs 'double'}} expected-note {{previous definition is here}}
@ -82,7 +82,7 @@ std::vector<WithDtor> getWithDtorVec() { std::vector<WithDtor> ret; ret.resize(7
cling::Value* VOnHeap = new cling::Value();
gCling->evaluate("getWithDtor()", *VOnHeap);
*VOnHeap //CHECK: (cling::Value) boxes [(WithDtor) @0x{{.*}}]
*VOnHeap //CHECK: (cling::Value &) boxes [(WithDtor) @0x{{.*}}]
WithDtor::fgCount //CHECK: (int) 1
delete VOnHeap;
WithDtor::fgCount //CHECK: (int) 0
@ -90,14 +90,14 @@ WithDtor::fgCount //CHECK: (int) 0
// Check destructor call for templates
VOnHeap = new cling::Value();
gCling->evaluate("getWithDtorVec()", *VOnHeap);
*VOnHeap //CHECK: (cling::Value) boxes [(std::vector<WithDtor>) @0x{{.*}}]
*VOnHeap //CHECK: (cling::Value &) boxes [(std::vector<WithDtor>) @0x{{.*}}]
WithDtor::fgCount //CHECK: (int) 7
delete VOnHeap;
WithDtor::fgCount //CHECK: (int) 0
// long doubles (tricky for the JIT).
gCling->evaluate("17.42L", V);
V // CHECK: (cling::Value) boxes [(long double) 17.42{{[0-9]*}}L]
V // CHECK: (cling::Value &) boxes [(long double) 17.42{{[0-9]*}}L]
// Test references, temporaries
.rawInput 1
@ -123,7 +123,7 @@ const Tracer& ConstRefMaker() {static Tracer R("CONSTREF"); return R;}
namespace cling {
// FIXME: inline printValue is not used by PrintClingValue()!
std::string printValue(const Tracer* const p, const Tracer* const u,
const ValuePrinterInfo& VPI) {
const Value& V) {
return p->asStr();
}
}
@ -139,7 +139,7 @@ gCling->evaluate("RefMaker()", V);
// This is the local static:
// CHECK: REF{1}:ctor
printf("RefMaker() done\n"); // CHECK-NEXT: RefMaker() done
V // CHECK-NEXT: (cling::Value) boxes [(Tracer &) @{{.*}}]
V // CHECK-NEXT: (cling::Value &) boxes [(Tracer &) @{{.*}}]
dumpTracerSVR(V); // CHECK-NEXT: REF{1}:dump
// Setting a new value should destruct the old - BUT it's a ref thus no
@ -152,7 +152,7 @@ gCling->evaluate("ObjMaker()", V);
// The temporary gets created:
// CHECK-NEXT:MADE{2}:ctor
printf("ObjMaker() done\n"); //CHECK-NEXT: ObjMaker() done
V // CHECK-NEXT: (cling::Value) boxes [(Tracer) @{{.*}}]
V // CHECK-NEXT: (cling::Value &) boxes [(Tracer) @{{.*}}]
dumpTracerSVR(V); // CHECK-NEXT: MADE{2}:dump
// Creating a variable:
@ -166,7 +166,7 @@ Tracer RT("VAR"); // CHECK-NEXT: VAR{3}:ctor
// CHECK-NEXT: MADE{2}:dtor
gCling->evaluate("RT", V); // should not call any ctor!
printf("RT done\n"); //CHECK-NEXT: RT done
V // CHECK-NEXT: (cling::Value) boxes [(Tracer &) @{{.*}}]
V // CHECK-NEXT: (cling::Value &) boxes [(Tracer &) @{{.*}}]
dumpTracerSVR(V); // CHECK-NEXT: VAR{2}:dump
// The following creates a copy, explicitly. This temporary object is then put
@ -176,7 +176,7 @@ gCling->evaluate("(Tracer)RT", V);
// Copies RT:
//CHECK-NEXT: VAR+{3}:copy
printf("(Tracer)RT done\n"); //CHECK-NEXT: RT done
V // CHECK-NEXT: (cling::Value) boxes [(Tracer) @{{.*}}]
V // CHECK-NEXT: (cling::Value &) boxes [(Tracer) @{{.*}}]
dumpTracerSVR(V); // CHECK-NEXT: VAR+{3}:dump
// Check eval of array var
@ -194,7 +194,7 @@ gCling->evaluate("arrV", V);
//CHECK-NEXT: MADE+{7}:copy
//CHECK-NEXT: MADE+{8}:copy
V // CHECK-NEXT: (cling::Value) boxes [(Tracer [3]) { @{{.*}}, @{{.*}}, @{{.*}} }]
V // CHECK-NEXT: (cling::Value &) boxes [(Tracer [3]) { @{{.*}}, @{{.*}}, @{{.*}} }]
// Destruct the variables with static storage:
// Destruct arrV:

View File

@ -28,7 +28,7 @@ gCling->process("a;", &V);
gCling->process("\"Root\"", &V);
// CHECK: (const char [5]) "Root"
V
// CHECK: (cling::Value) boxes [(const char *) "Root"]
// CHECK: (cling::Value &) boxes [(const char [5]) "Root"]
// End PR #98146
typedef enum {k1,k2} enumName;
enumName var

View File

@ -14,12 +14,12 @@ const char* b = "b" // CHECK: (const char *) "b"
const char* n = 0 // CHECK: (const char *) <<<NULL>>
struct C {int d;} E = {22};
E // CHECK: (struct C) @0x{{[0-9A-Fa-f]{6,12}.}}
E // CHECK: (struct C &) @0x{{[0-9A-Fa-f]{6,12}.}}
E.d // CHECK: (int) 22
#include <string>
std::string s("xyz")
// CHECK: (std::string) @0x{{[0-9A-Fa-f]{6,12}.}}
// CHECK: (std::string &) @0x{{[0-9A-Fa-f]{6,12}.}}
// CHECK: c_str: "xyz"
#include <limits.h>