text stringlengths 54 60.6k |
|---|
<commit_before>
/****************************************************************************
*
* Copyright (C) 2014 PX4 Development Team. All rights reserved.
*
* 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 PX4 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.
*
****************************************************************************/
/**
* @file publisher_example.cpp
* Example subscriber for ros and px4
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "publisher_example.h"
using namespace px4;
PublisherExample::PublisherExample() :
_n(appState),
_rc_channels_pub(_n.advertise<px4_rc_channels>()),
_v_att_pub(_n.advertise<px4_vehicle_attitude>()),
_parameter_update_pub(_n.advertise<px4_parameter_update>())
{
}
px4::AppState PublisherExample::appState;
int PublisherExample::main()
{
px4::Rate loop_rate(10);
while (!appState.exitRequested()) {
loop_rate.sleep();
_n.spinOnce();
/* Publish example message */
px4_rc_channels rc_channels_msg;
rc_channels_msg.data().timestamp_last_valid = px4::get_time_micros();
PX4_INFO("rc: %llu", rc_channels_msg.data().timestamp_last_valid);
_rc_channels_pub->publish(rc_channels_msg);
/* Publish example message */
px4_vehicle_attitude v_att_msg;
v_att_msg.data().timestamp = px4::get_time_micros();
PX4_INFO("att: %llu", v_att_msg.data().timestamp);
_v_att_pub->publish(v_att_msg);
/* Publish example message */
px4_parameter_update parameter_update_msg;
parameter_update_msg.data().timestamp = px4::get_time_micros();
PX4_INFO("param update: %llu", parameter_update_msg.data().timestamp);
_parameter_update_pub->publish(parameter_update_msg);
}
return 0;
}
<commit_msg>ROS: Fixes for print of uint64_t type<commit_after>
/****************************************************************************
*
* Copyright (C) 2014 PX4 Development Team. All rights reserved.
*
* 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 PX4 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.
*
****************************************************************************/
/**
* @file publisher_example.cpp
* Example subscriber for ros and px4
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "publisher_example.h"
using namespace px4;
PublisherExample::PublisherExample() :
_n(appState),
_rc_channels_pub(_n.advertise<px4_rc_channels>()),
_v_att_pub(_n.advertise<px4_vehicle_attitude>()),
_parameter_update_pub(_n.advertise<px4_parameter_update>())
{
}
px4::AppState PublisherExample::appState;
int PublisherExample::main()
{
px4::Rate loop_rate(10);
while (!appState.exitRequested()) {
loop_rate.sleep();
_n.spinOnce();
/* Publish example message */
px4_rc_channels rc_channels_msg;
rc_channels_msg.data().timestamp_last_valid = px4::get_time_micros();
PX4_INFO("rc: %" PRIu64, rc_channels_msg.data().timestamp_last_valid);
_rc_channels_pub->publish(rc_channels_msg);
/* Publish example message */
px4_vehicle_attitude v_att_msg;
v_att_msg.data().timestamp = px4::get_time_micros();
PX4_INFO("att: %" PRIu64, v_att_msg.data().timestamp);
_v_att_pub->publish(v_att_msg);
/* Publish example message */
px4_parameter_update parameter_update_msg;
parameter_update_msg.data().timestamp = px4::get_time_micros();
PX4_INFO("param update: %" PRIu64, parameter_update_msg.data().timestamp);
_parameter_update_pub->publish(parameter_update_msg);
}
return 0;
}
<|endoftext|> |
<commit_before>// Copyright (C) 2016 Elviss Strazdins
// This file is part of the Ouzel engine.
#define NOMINMAX
#include <windows.h>
#include "WindowWin.h"
#include "core/Engine.h"
#include "utils/Utils.h"
void ouzelMain(const std::vector<std::string>& args);
int WINAPI WinMain(HINSTANCE hInstance,
HINSTANCE hPrevInstance,
LPSTR lpCmdLine,
int nCmdShow)
{
OUZEL_UNUSED(hInstance);
OUZEL_UNUSED(hPrevInstance);
OUZEL_UNUSED(lpCmdLine);
OUZEL_UNUSED(nCmdShow);
LPWSTR* argList;
int nArgs;
int i;
argList = CommandLineToArgvW(GetCommandLineW(), &nArgs);
std::vector<std::string> args;
if (argList)
{
for (i = 0; i < nArgs; i++)
{
char temporaryCString[256];
WideCharToMultiByte(CP_UTF8, 0, argList[i], -1, temporaryCString, sizeof(temporaryCString), nullptr, nullptr);
args.push_back(temporaryCString);
}
LocalFree(argList);
}
ouzel::setArgs(args);
ouzelMain(ouzel::getArgs());
if (!ouzel::sharedEngine)
{
return 0;
}
std::shared_ptr<ouzel::WindowWin> window = std::static_pointer_cast<ouzel::WindowWin>(ouzel::sharedEngine->getWindow());
ouzel::sharedEngine->begin();
MSG msg;
bool running = true;
while (running)
{
std::set<HACCEL> accelerators = window->getAccelerators();
while (PeekMessage(&msg, NULL, 0, 0, PM_REMOVE))
{
bool translate = true;
for (HACCEL accelerator : accelerators)
{
if (TranslateAccelerator(window->getNativeWindow(), accelerator, &msg))
{
translate = false;
}
}
if (translate)
{
TranslateMessage(&msg);
DispatchMessage(&msg);
}
if (msg.message == WM_QUIT)
{
running = false;
}
}
if (!ouzel::sharedEngine->run())
{
running = false;
}
}
ouzel::sharedEngine->end();
return 0;
}
<commit_msg>Use nullptr instead of NULL<commit_after>// Copyright (C) 2016 Elviss Strazdins
// This file is part of the Ouzel engine.
#define NOMINMAX
#include <windows.h>
#include "WindowWin.h"
#include "core/Engine.h"
#include "utils/Utils.h"
void ouzelMain(const std::vector<std::string>& args);
int WINAPI WinMain(HINSTANCE hInstance,
HINSTANCE hPrevInstance,
LPSTR lpCmdLine,
int nCmdShow)
{
OUZEL_UNUSED(hInstance);
OUZEL_UNUSED(hPrevInstance);
OUZEL_UNUSED(lpCmdLine);
OUZEL_UNUSED(nCmdShow);
LPWSTR* argList;
int nArgs;
int i;
argList = CommandLineToArgvW(GetCommandLineW(), &nArgs);
std::vector<std::string> args;
if (argList)
{
for (i = 0; i < nArgs; i++)
{
char temporaryCString[256];
WideCharToMultiByte(CP_UTF8, 0, argList[i], -1, temporaryCString, sizeof(temporaryCString), nullptr, nullptr);
args.push_back(temporaryCString);
}
LocalFree(argList);
}
ouzel::setArgs(args);
ouzelMain(ouzel::getArgs());
if (!ouzel::sharedEngine)
{
return 0;
}
std::shared_ptr<ouzel::WindowWin> window = std::static_pointer_cast<ouzel::WindowWin>(ouzel::sharedEngine->getWindow());
ouzel::sharedEngine->begin();
MSG msg;
bool running = true;
while (running)
{
std::set<HACCEL> accelerators = window->getAccelerators();
while (PeekMessage(&msg, nullptr, 0, 0, PM_REMOVE))
{
bool translate = true;
for (HACCEL accelerator : accelerators)
{
if (TranslateAccelerator(window->getNativeWindow(), accelerator, &msg))
{
translate = false;
}
}
if (translate)
{
TranslateMessage(&msg);
DispatchMessage(&msg);
}
if (msg.message == WM_QUIT)
{
running = false;
}
}
if (!ouzel::sharedEngine->run())
{
running = false;
}
}
ouzel::sharedEngine->end();
return 0;
}
<|endoftext|> |
<commit_before>/*
* Copyright (C) 2012
* Alessio Sclocco <a.sclocco@vu.nl>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#include <iostream>
#include <string>
#include <vector>
#include <exception>
#include <fstream>
#include <iomanip>
#include <limits>
#include <cmath>
#include <ctime>
using std::cout;
using std::cerr;
using std::endl;
using std::string;
using std::vector;
using std::exception;
using std::ofstream;
using std::fixed;
using std::setprecision;
using std::numeric_limits;
#include <ArgumentList.hpp>
#include <Observation.hpp>
#include <InitializeOpenCL.hpp>
#include <CLData.hpp>
#include <utils.hpp>
#include <Folding.hpp>
#include <FoldingCPU.hpp>
using isa::utils::ArgumentList;
using isa::utils::same;
using AstroData::Observation;
using isa::OpenCL::initializeOpenCL;
using isa::OpenCL::CLData;
using PulsarSearch::folding;
using PulsarSearch::Folding;
typedef float dataType;
const string typeName("float");
const unsigned int padding = 32;
// Common parameters
const unsigned int nrBeams = 1;
const unsigned int nrStations = 64;
// LOFAR
/*const float minFreq = 138.965f;
const float channelBandwidth = 0.195f;
const unsigned int nrSamplesPerSecond = 200000;
const unsigned int nrChannels = 32;*/
// Apertif
const float minFreq = 1425.0f;
const float channelBandwidth = 0.2929f;
const unsigned int nrSamplesPerSecond = 20000;
const unsigned int nrChannels = 1024;
// DMs
const unsigned int nrDMs = 256;
// Periods
const unsigned int nrPeriods = 128;
const unsigned int nrBins = 256;
int main(int argc, char *argv[]) {
unsigned int clPlatformID = 0;
unsigned int clDeviceID = 0;
long long unsigned int wrongValues = 0;
Observation< dataType > observation("FoldingTest", typeName);
CLData< dataType > * dedispersedData = new CLData< dataType >("DedispersedData", true);
CLData< dataType > * foldedData = new CLData<dataType >("FoldedData", true);
CLData< unsigned int > * counterData = new CLData< unsigned int >("CounterData", true);
try {
ArgumentList args(argc, argv);
clPlatformID = args.getSwitchArgument< unsigned int >("-opencl_platform");
clDeviceID = args.getSwitchArgument< unsigned int >("-opencl_device");
} catch ( exception &err ) {
cerr << err.what() << endl;
return 1;
}
// Setup of the observation
observation.setPadding(padding);
observation.setNrSamplesPerSecond(nrSamplesPerSecond);
observation.setNrDMs(nrDMs);
observation.setNrPeriods(nrPeriods);
observation.setFirstPeriod(nrBins);
observation.setPeriodStep(nrBins);
observation.setNrBins(nrBins);
cl::Context * clContext = new cl::Context();
vector< cl::Platform > * clPlatforms = new vector< cl::Platform >();
vector< cl::Device > * clDevices = new vector< cl::Device >();
vector< vector< cl::CommandQueue > > * clQueues = new vector< vector < cl::CommandQueue > >();
initializeOpenCL(clPlatformID, 1, clPlatforms, clContext, clDevices, clQueues);
// Allocate memory
dedispersedData->allocateHostData(observation.getNrSamplesPerSecond() * observation.getNrPaddedDMs());
foldedData->allocateHostData(observation.getNrPaddedDMs() * observation.getNrBins() * observation.getNrPeriods());
foldedData->blankHostData();
counterData->allocateHostData(observation.getNrPaddedDMs() * observation.getNrBins() * observation.getNrPeriods());
counterData->blankHostData();
dedispersedData->setCLContext(clContext);
dedispersedData->setCLQueue(&((clQueues->at(clDeviceID)).at(0)));
foldedData->setCLContext(clContext);
foldedData->setCLQueue(&((clQueues->at(clDeviceID)).at(0)));
counterData->setCLContext(clContext);
counterData->setCLQueue(&((clQueues->at(clDeviceID)).at(0)));
try {
dedispersedData->allocateDeviceData();
foldedData->allocateDeviceData();
foldedData->copyHostToDevice();
counterData->allocateDeviceData();
counterData->copyHostToDevice();
} catch ( OpenCLError err ) {
cerr << err.what() << endl;
return 1;
}
srand(time(NULL));
for ( unsigned int sample = 0; sample < observation.getNrSamplesPerSecond(); sample++ ) {
for ( unsigned int DM = 0; DM < observation.getNrDMs(); DM++ ) {
dedispersedData->setHostDataItem((sample * observation.getNrPaddedDMs()) + DM, rand() % 100);
}
}
// Test
try {
// Generate kernel
Folding< dataType > clFold("clFold", typeName);
clFold.bindOpenCL(clContext, &(clDevices->at(clDeviceID)), &((clQueues->at(clDeviceID)).at(0)));
clFold.setObservation(&observation);
clFold.setNrDMsPerBlock(128);
clFold.setNrPeriodsPerBlock(2);
clFold.setNrBinsPerBlock(1);
clFold.setNrDMsPerThread(2);
clFold.setNrPeriodsPerThread(2);
clFold.setNrBinsPerThread(4);
clFold.generateCode();
dedispersedData->copyHostToDevice();
clFold(dedispersedData, foldedData, counterData);
foldedData->copyDeviceToHost();
} catch ( OpenCLError err ) {
cerr << err.what() << endl;
return 1;
}
// Check
CLData< dataType > * CPUFolded = new CLData<dataType >("CPUFolded", true);
CLData< unsigned int > * CPUCounter = new CLData< unsigned int >("CPUCounter", true);
folding(0, observation, dedispersedData->getHostData(), CPUFolded->getHostData(), CPUCounter->getHostData());
for ( unsigned int bin = 0; bin < observation.getNrBins(); bin++ ) {
for ( unsigned int period = 0; period < observation.getNrPeriods(); period++ ) {
for ( unsigned int DM = 0; DM < observation.getNrDMs(); DM++ ) {
const unsigned int dataItem = (bin * observation.getNrPeriods() * observation.getNrPaddedDMs()) + (period * observation.getNrPaddedDMs()) + DM;
if ( !same(CPUFolded->getHostDataItem(dataItem), foldedData->getHostDataItem(dataItem)) ) {
wrongValues++;
}
}
}
}
cout << "Wrong samples: " << wrongValues << " (" << (wrongValues * 100) / (static_cast< long long unsigned int >(observation.getNrDMs()) * observation.getNrPeriods() * observation.getNrBins()) << "%)." << endl;
cout << endl;
return 0;
}
<commit_msg>Forgot to allocate memory for the CPU.<commit_after>/*
* Copyright (C) 2012
* Alessio Sclocco <a.sclocco@vu.nl>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#include <iostream>
#include <string>
#include <vector>
#include <exception>
#include <fstream>
#include <iomanip>
#include <limits>
#include <cmath>
#include <ctime>
using std::cout;
using std::cerr;
using std::endl;
using std::string;
using std::vector;
using std::exception;
using std::ofstream;
using std::fixed;
using std::setprecision;
using std::numeric_limits;
#include <ArgumentList.hpp>
#include <Observation.hpp>
#include <InitializeOpenCL.hpp>
#include <CLData.hpp>
#include <utils.hpp>
#include <Folding.hpp>
#include <FoldingCPU.hpp>
using isa::utils::ArgumentList;
using isa::utils::same;
using AstroData::Observation;
using isa::OpenCL::initializeOpenCL;
using isa::OpenCL::CLData;
using PulsarSearch::folding;
using PulsarSearch::Folding;
typedef float dataType;
const string typeName("float");
const unsigned int padding = 32;
// Common parameters
const unsigned int nrBeams = 1;
const unsigned int nrStations = 64;
// LOFAR
/*const float minFreq = 138.965f;
const float channelBandwidth = 0.195f;
const unsigned int nrSamplesPerSecond = 200000;
const unsigned int nrChannels = 32;*/
// Apertif
const float minFreq = 1425.0f;
const float channelBandwidth = 0.2929f;
const unsigned int nrSamplesPerSecond = 20000;
const unsigned int nrChannels = 1024;
// DMs
const unsigned int nrDMs = 256;
// Periods
const unsigned int nrPeriods = 128;
const unsigned int nrBins = 256;
int main(int argc, char *argv[]) {
unsigned int clPlatformID = 0;
unsigned int clDeviceID = 0;
long long unsigned int wrongValues = 0;
Observation< dataType > observation("FoldingTest", typeName);
CLData< dataType > * dedispersedData = new CLData< dataType >("DedispersedData", true);
CLData< dataType > * foldedData = new CLData<dataType >("FoldedData", true);
CLData< unsigned int > * counterData = new CLData< unsigned int >("CounterData", true);
try {
ArgumentList args(argc, argv);
clPlatformID = args.getSwitchArgument< unsigned int >("-opencl_platform");
clDeviceID = args.getSwitchArgument< unsigned int >("-opencl_device");
} catch ( exception &err ) {
cerr << err.what() << endl;
return 1;
}
// Setup of the observation
observation.setPadding(padding);
observation.setNrSamplesPerSecond(nrSamplesPerSecond);
observation.setNrDMs(nrDMs);
observation.setNrPeriods(nrPeriods);
observation.setFirstPeriod(nrBins);
observation.setPeriodStep(nrBins);
observation.setNrBins(nrBins);
cl::Context * clContext = new cl::Context();
vector< cl::Platform > * clPlatforms = new vector< cl::Platform >();
vector< cl::Device > * clDevices = new vector< cl::Device >();
vector< vector< cl::CommandQueue > > * clQueues = new vector< vector < cl::CommandQueue > >();
initializeOpenCL(clPlatformID, 1, clPlatforms, clContext, clDevices, clQueues);
// Allocate memory
dedispersedData->allocateHostData(observation.getNrSamplesPerSecond() * observation.getNrPaddedDMs());
foldedData->allocateHostData(observation.getNrPaddedDMs() * observation.getNrBins() * observation.getNrPeriods());
foldedData->blankHostData();
counterData->allocateHostData(observation.getNrPaddedDMs() * observation.getNrBins() * observation.getNrPeriods());
counterData->blankHostData();
dedispersedData->setCLContext(clContext);
dedispersedData->setCLQueue(&((clQueues->at(clDeviceID)).at(0)));
foldedData->setCLContext(clContext);
foldedData->setCLQueue(&((clQueues->at(clDeviceID)).at(0)));
counterData->setCLContext(clContext);
counterData->setCLQueue(&((clQueues->at(clDeviceID)).at(0)));
try {
dedispersedData->allocateDeviceData();
foldedData->allocateDeviceData();
foldedData->copyHostToDevice();
counterData->allocateDeviceData();
counterData->copyHostToDevice();
} catch ( OpenCLError err ) {
cerr << err.what() << endl;
return 1;
}
srand(time(NULL));
for ( unsigned int sample = 0; sample < observation.getNrSamplesPerSecond(); sample++ ) {
for ( unsigned int DM = 0; DM < observation.getNrDMs(); DM++ ) {
dedispersedData->setHostDataItem((sample * observation.getNrPaddedDMs()) + DM, rand() % 100);
}
}
// Test
try {
// Generate kernel
Folding< dataType > clFold("clFold", typeName);
clFold.bindOpenCL(clContext, &(clDevices->at(clDeviceID)), &((clQueues->at(clDeviceID)).at(0)));
clFold.setObservation(&observation);
clFold.setNrDMsPerBlock(128);
clFold.setNrPeriodsPerBlock(2);
clFold.setNrBinsPerBlock(1);
clFold.setNrDMsPerThread(2);
clFold.setNrPeriodsPerThread(2);
clFold.setNrBinsPerThread(4);
clFold.generateCode();
dedispersedData->copyHostToDevice();
clFold(dedispersedData, foldedData, counterData);
foldedData->copyDeviceToHost();
} catch ( OpenCLError err ) {
cerr << err.what() << endl;
return 1;
}
// Check
CLData< dataType > * CPUFolded = new CLData<dataType >("CPUFolded", true);
CLData< unsigned int > * CPUCounter = new CLData< unsigned int >("CPUCounter", true);
CPUFolded.allocateHostData(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
CPUCounter.allocateHostData(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
folding(0, observation, dedispersedData->getHostData(), CPUFolded->getHostData(), CPUCounter->getHostData());
for ( unsigned int bin = 0; bin < observation.getNrBins(); bin++ ) {
for ( unsigned int period = 0; period < observation.getNrPeriods(); period++ ) {
for ( unsigned int DM = 0; DM < observation.getNrDMs(); DM++ ) {
const unsigned int dataItem = (bin * observation.getNrPeriods() * observation.getNrPaddedDMs()) + (period * observation.getNrPaddedDMs()) + DM;
if ( !same(CPUFolded->getHostDataItem(dataItem), foldedData->getHostDataItem(dataItem)) ) {
wrongValues++;
}
}
}
}
cout << "Wrong samples: " << wrongValues << " (" << (wrongValues * 100) / (static_cast< long long unsigned int >(observation.getNrDMs()) * observation.getNrPeriods() * observation.getNrBins()) << "%)." << endl;
cout << endl;
return 0;
}
<|endoftext|> |
<commit_before>// Copyright 2014 Alessio Sclocco <a.sclocco@vu.nl>
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <iostream>
#include <string>
#include <vector>
#include <exception>
#include <fstream>
#include <iomanip>
#include <limits>
#include <ctime>
#include <ArgumentList.hpp>
#include <Exceptions.hpp>
#include <Observation.hpp>
#include <InitializeOpenCL.hpp>
#include <Kernel.hpp>
#include <utils.hpp>
#include <Bins.hpp>
#include <Folding.hpp>
typedef float dataType;
std::string typeName("float");
int main(int argc, char *argv[]) {
bool print = false;
unsigned int clPlatformID = 0;
unsigned int clDeviceID = 0;
unsigned int nrDMsPerBlock = 0;
unsigned int nrPeriodsPerBlock = 0;
unsigned int nrBinsPerBlock = 0;
unsigned int nrDMsPerThread = 0;
unsigned int nrPeriodsPerThread = 0;
unsigned int nrBinsPerThread = 0;
long long unsigned int wrongSamples = 0;
AstroData::Observation< dataType > observation("FoldingTest", typeName);
try {
isa::utils::ArgumentList args(argc, argv);
print = args.getSwitch("-print");
clPlatformID = args.getSwitchArgument< unsigned int >("-opencl_platform");
clDeviceID = args.getSwitchArgument< unsigned int >("-opencl_device");
observation.setPadding(args.getSwitchArgument< unsigned int >("-padding"));
nrDMsPerBlock = args.getSwitchArgument< unsigned int >("-db");
nrPeriodsPerBlock = args.getSwitchArgument< unsigned int >("-pb");
nrBinsPerBlock = args.getSwitchArgument< unsigned int >("-bb");
nrDMsPerThread = args.getSwitchArgument< unsigned int >("-dt");
nrPeriodsPerThread = args.getSwitchArgument< unsigned int >("-pt");
nrBinsPerThread = args.getSwitchArgument< unsigned int >("-bt");
observation.setNrSeconds(args.getSwitchArgument< unsigned int >("-seconds"));
observation.setNrSamplesPerSecond(args.getSwitchArgument< unsigned int >("-samples"));
observation.setNrDMs(args.getSwitchArgument< unsigned int >("-dms"));
observation.setNrPeriods(args.getSwitchArgument< unsigned int >("-periods"));
observation.setNrBins(args.getSwitchArgument< unsigned int >("-bins"));
observation.setFirstPeriod(args.getSwitchArgument< unsigned int >("-first_period"));
observation.setPeriodStep(args.getSwitchArgument< unsigned int >("-period_step"));
} catch ( isa::Exceptions::SwitchNotFound &err ) {
std::cerr << err.what() << std::endl;
return 1;
}catch ( std::exception &err ) {
std::cerr << "Usage: " << argv[0] << " [-print] -opencl_platform ... -opencl_device ... -padding ... -db ... -pb ... -bb ... -dt ... -pt ... -bt ... -seconds .... -samples ... -dms ... -periods ... -bins ... -first_period ... -period_step ..." << std::endl;
return 1;
}
// Initialize OpenCL
cl::Context * clContext = new cl::Context();
std::vector< cl::Platform > * clPlatforms = new std::vector< cl::Platform >();
std::vector< cl::Device > * clDevices = new std::vector< cl::Device >();
std::vector< std::vector< cl::CommandQueue > > * clQueues = new std::vector< std::vector < cl::CommandQueue > >();
isa::OpenCL::initializeOpenCL(clPlatformID, 1, clPlatforms, clContext, clDevices, clQueues);
std::vector< unsigned int > * samplesPerBin = PulsarSearch::getSamplesPerBin(observation);
// Allocate memory
cl::Buffer samplesPerBin_d;
std::vector< std::vector< dataType > * > dedispersedData = std::vector< std::vector< dataType > * >(observation.getNrSeconds());
std::vector< std::vector< dataType > * > dedispersedData_c = std::vector< std::vector< dataType > * >(observation.getNrSeconds());
for ( unsigned int second = 0; second < observation.getNrSeconds(); second++ ) {
dedispersedData.at(second) = new std::vector< dataType >(observation.getNrSamplesPerSecond() * observation.getNrPaddedDMs());
dedispersedData_c.at(second) = new std::vector< dataType >(observation.getNrDMs() * observation.getNrSamplesPerPaddedSecond());
}
cl::Buffer dedispersedData_d;
std::vector< dataType > foldedData_c = std::vector< dataType >(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
std::vector< dataType > foldedData = std::vector< dataType >(observation.getNrDMs() * observation.getNrPeriods() * observation.getNrPaddedBins());
cl::Buffer foldedData_d;
std::vector< unsigned int > counters_c = std::vector< unsigned int >(observation.getNrDMs() * observation.getNrPeriods() * observation.getNrPaddedBins());
std::vector< unsigned int > readCounters = std::vector< unsigned int >(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
cl::Buffer readCounters_d;
std::vector< unsigned int > writeCounters = std::vector< unsigned int >(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
cl::Buffer writeCounters_d;
try {
samplesPerBin_d = cl::Buffer(*clContext, CL_MEM_READ_ONLY, samplesPerBin->size() * sizeof(unsigned int), NULL, NULL);
dedispersedData_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, (dedispersedData.at(0))->size() * sizeof(dataType), NULL, NULL);
foldedData_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, foldedData.size() * sizeof(dataType), NULL, NULL);
readCounters_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, readCounters.size() * sizeof(unsigned int), NULL, NULL);
writeCounters_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, writeCounters.size() * sizeof(unsigned int), NULL, NULL);
} catch ( cl::Error &err ) {
std::cerr << "OpenCL error allocating memory: " << isa::utils::toString< cl_int >(err.err()) << "." << std::endl;
return 1;
}
srand(time(NULL));
for ( unsigned int second = 0; second < observation.getNrSeconds(); second++ ) {
for ( unsigned int sample = 0; sample < observation.getNrSamplesPerSecond(); sample++ ) {
for ( unsigned int dm = 0; dm < observation.getNrDMs(); dm++ ) {
(dedispersedData.at(second))->at((sample * observation.getNrPaddedDMs()) + dm) = static_cast< dataType >(rand() % 10);
dedispersedData_c.at(second)[(dm * observation.getNrSamplesPerPaddedSecond()) + sample] = dedispersedData.at(second)[(sample * observation.getNrPaddedDMs()) + dm];
}
}
}
std::fill(foldedData.begin(), foldedData.end(), static_cast< dataType >(0));
std::fill(foldedData_c.begin(), foldedData_c.end(), static_cast< dataType >(0));
std::fill(counters_c.begin(), counters_c.end(), 0);
std::fill(readCounters.begin(), readCounters.end(), 0);
std::fill(writeCounters.begin(), writeCounters.end(), 0);
// Copy data structures to device
try {
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(samplesPerBin_d, CL_FALSE, 0, samplesPerBin->size() * sizeof(unsigned int), reinterpret_cast< void * >(samplesPerBin->data()));
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(foldedData_d, CL_FALSE, 0, foldedData.size() * sizeof(dataType), reinterpret_cast< void * >(foldedData.data()));
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(readCounters_d, CL_FALSE, 0, readCounters.size() * sizeof(unsigned int), reinterpret_cast< void * >(readCounters.data()));
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(writeCounters_d, CL_FALSE, 0, writeCounters.size() * sizeof(unsigned int), reinterpret_cast< void * >(writeCounters.data()));
} catch ( cl::Error &err ) {
std::cerr << "OpenCL error H2D transfer: " << isa::utils::toString< cl_int >(err.err()) << "." << std::endl;
return 1;
}
// Generate kernel
cl::Kernel * kernel;
std::string * code = PulsarSearch::getFoldingOpenCL(nrDMsPerBlock, nrPeriodsPerBlock, nrBinsPerBlock, nrDMsPerThread, nrPeriodsPerThread, nrBinsPerThread, typeName, observation);
if ( print ) {
std::cout << *code << std::endl;
}
try {
kernel = isa::OpenCL::compile("folding", *code, "-cl-mad-enable -Werror", *clContext, clDevices->at(clDeviceID));
} catch ( isa::Exceptions::OpenCLError &err ) {
std::cerr << err.what() << std::endl;
return 1;
}
// Run OpenCL kernel and CPU control
try {
cl::NDRange global(observation.getNrPaddedDMs() / nrDMsPerThread, observation.getNrPeriods() / nrPeriodsPerThread, observation.getNrBins() / nrBinsPerThread);
cl::NDRange local(nrDMsPerBlock, nrPeriodsPerBlock, nrBinsPerBlock);
kernel->setArg(1, dedispersedData_d);
kernel->setArg(2, foldedData_d);
kernel->setArg(5, samplesPerBin_d);
for ( unsigned int second = 0; second < observation.getNrSeconds(); second++ ) {
kernel->setArg(0, second);
if ( second % 2 == 0 ) {
kernel->setArg(3, readCounters_d);
kernel->setArg(4, writeCounters_d);
} else {
kernel->setArg(3, writeCounters_d);
kernel->setArg(4, readCounters_d);
}
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(dedispersedData_d, CL_FALSE, 0, (dedispersedData.at(second))->size() * sizeof(dataType), reinterpret_cast< void * >((dedispersedData.at(second))->data()));
clQueues->at(clDeviceID)[0].enqueueNDRangeKernel(*kernel, cl::NullRange, global, local);
PulsarSearch::folding(second, observation, *(dedispersedData_c.at(second)), foldedData_c, counters_c);
}
clQueues->at(clDeviceID)[0].enqueueReadBuffer(foldedData_d, CL_TRUE, 0, foldedData.size() * sizeof(dataType), reinterpret_cast< void * >(foldedData.data()));
} catch ( cl::Error &err ) {
std::cerr << "OpenCL error: " << isa::utils::toString< cl_int >(err.err()) << "." << std::endl;
return 1;
}
for ( unsigned int dm = 0; dm < observation.getNrDMs(); dm++ ) {
for ( unsigned int period = 0; period < observation.getNrPeriods(); period++ ) {
for ( unsigned int bin = 0; bin < observation.getNrBins(); bin++ ) {
if ( ! isa::utils::same(foldedData_c[(dm * observation.getNrPeriods() * observation.getNrPaddedBins()) + (period * observation.getNrPaddedBins()) + bin], foldedData[(bin * observation.getNrPeriods() * observation.getNrPaddedDMs()) * (period * observation.getNrPaddedDMs()) + dm]) ) {
wrongSamples++;
}
}
}
}
if ( wrongSamples > 0 ) {
std::cout << "Wrong samples: " << wrongSamples << " (" << (wrongSamples * 100.0) / (static_cast< long long unsigned int >(observation.getNrDMs()) * observation.getNrPeriods() * observation.getNrBins()) << "%)." << std::endl;
} else {
std::cout << "TEST PASSED." << std::endl;
}
return 0;
}
<commit_msg>Small fix for vectors.<commit_after>// Copyright 2014 Alessio Sclocco <a.sclocco@vu.nl>
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <iostream>
#include <string>
#include <vector>
#include <exception>
#include <fstream>
#include <iomanip>
#include <limits>
#include <ctime>
#include <ArgumentList.hpp>
#include <Exceptions.hpp>
#include <Observation.hpp>
#include <InitializeOpenCL.hpp>
#include <Kernel.hpp>
#include <utils.hpp>
#include <Bins.hpp>
#include <Folding.hpp>
typedef float dataType;
std::string typeName("float");
int main(int argc, char *argv[]) {
bool print = false;
unsigned int clPlatformID = 0;
unsigned int clDeviceID = 0;
unsigned int nrDMsPerBlock = 0;
unsigned int nrPeriodsPerBlock = 0;
unsigned int nrBinsPerBlock = 0;
unsigned int nrDMsPerThread = 0;
unsigned int nrPeriodsPerThread = 0;
unsigned int nrBinsPerThread = 0;
long long unsigned int wrongSamples = 0;
AstroData::Observation< dataType > observation("FoldingTest", typeName);
try {
isa::utils::ArgumentList args(argc, argv);
print = args.getSwitch("-print");
clPlatformID = args.getSwitchArgument< unsigned int >("-opencl_platform");
clDeviceID = args.getSwitchArgument< unsigned int >("-opencl_device");
observation.setPadding(args.getSwitchArgument< unsigned int >("-padding"));
nrDMsPerBlock = args.getSwitchArgument< unsigned int >("-db");
nrPeriodsPerBlock = args.getSwitchArgument< unsigned int >("-pb");
nrBinsPerBlock = args.getSwitchArgument< unsigned int >("-bb");
nrDMsPerThread = args.getSwitchArgument< unsigned int >("-dt");
nrPeriodsPerThread = args.getSwitchArgument< unsigned int >("-pt");
nrBinsPerThread = args.getSwitchArgument< unsigned int >("-bt");
observation.setNrSeconds(args.getSwitchArgument< unsigned int >("-seconds"));
observation.setNrSamplesPerSecond(args.getSwitchArgument< unsigned int >("-samples"));
observation.setNrDMs(args.getSwitchArgument< unsigned int >("-dms"));
observation.setNrPeriods(args.getSwitchArgument< unsigned int >("-periods"));
observation.setNrBins(args.getSwitchArgument< unsigned int >("-bins"));
observation.setFirstPeriod(args.getSwitchArgument< unsigned int >("-first_period"));
observation.setPeriodStep(args.getSwitchArgument< unsigned int >("-period_step"));
} catch ( isa::Exceptions::SwitchNotFound &err ) {
std::cerr << err.what() << std::endl;
return 1;
}catch ( std::exception &err ) {
std::cerr << "Usage: " << argv[0] << " [-print] -opencl_platform ... -opencl_device ... -padding ... -db ... -pb ... -bb ... -dt ... -pt ... -bt ... -seconds .... -samples ... -dms ... -periods ... -bins ... -first_period ... -period_step ..." << std::endl;
return 1;
}
// Initialize OpenCL
cl::Context * clContext = new cl::Context();
std::vector< cl::Platform > * clPlatforms = new std::vector< cl::Platform >();
std::vector< cl::Device > * clDevices = new std::vector< cl::Device >();
std::vector< std::vector< cl::CommandQueue > > * clQueues = new std::vector< std::vector < cl::CommandQueue > >();
isa::OpenCL::initializeOpenCL(clPlatformID, 1, clPlatforms, clContext, clDevices, clQueues);
std::vector< unsigned int > * samplesPerBin = PulsarSearch::getSamplesPerBin(observation);
// Allocate memory
cl::Buffer samplesPerBin_d;
std::vector< std::vector< dataType > * > dedispersedData = std::vector< std::vector< dataType > * >(observation.getNrSeconds());
std::vector< std::vector< dataType > * > dedispersedData_c = std::vector< std::vector< dataType > * >(observation.getNrSeconds());
for ( unsigned int second = 0; second < observation.getNrSeconds(); second++ ) {
dedispersedData.at(second) = new std::vector< dataType >(observation.getNrSamplesPerSecond() * observation.getNrPaddedDMs());
dedispersedData_c.at(second) = new std::vector< dataType >(observation.getNrDMs() * observation.getNrSamplesPerPaddedSecond());
}
cl::Buffer dedispersedData_d;
std::vector< dataType > foldedData_c = std::vector< dataType >(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
std::vector< dataType > foldedData = std::vector< dataType >(observation.getNrDMs() * observation.getNrPeriods() * observation.getNrPaddedBins());
cl::Buffer foldedData_d;
std::vector< unsigned int > counters_c = std::vector< unsigned int >(observation.getNrDMs() * observation.getNrPeriods() * observation.getNrPaddedBins());
std::vector< unsigned int > readCounters = std::vector< unsigned int >(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
cl::Buffer readCounters_d;
std::vector< unsigned int > writeCounters = std::vector< unsigned int >(observation.getNrBins() * observation.getNrPeriods() * observation.getNrPaddedDMs());
cl::Buffer writeCounters_d;
try {
samplesPerBin_d = cl::Buffer(*clContext, CL_MEM_READ_ONLY, samplesPerBin->size() * sizeof(unsigned int), NULL, NULL);
dedispersedData_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, (dedispersedData.at(0))->size() * sizeof(dataType), NULL, NULL);
foldedData_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, foldedData.size() * sizeof(dataType), NULL, NULL);
readCounters_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, readCounters.size() * sizeof(unsigned int), NULL, NULL);
writeCounters_d = cl::Buffer(*clContext, CL_MEM_READ_WRITE, writeCounters.size() * sizeof(unsigned int), NULL, NULL);
} catch ( cl::Error &err ) {
std::cerr << "OpenCL error allocating memory: " << isa::utils::toString< cl_int >(err.err()) << "." << std::endl;
return 1;
}
srand(time(NULL));
for ( unsigned int second = 0; second < observation.getNrSeconds(); second++ ) {
for ( unsigned int sample = 0; sample < observation.getNrSamplesPerSecond(); sample++ ) {
for ( unsigned int dm = 0; dm < observation.getNrDMs(); dm++ ) {
(dedispersedData.at(second))->at((sample * observation.getNrPaddedDMs()) + dm) = static_cast< dataType >(rand() % 10);
(dedispersedData_c.at(second))->at((dm * observation.getNrSamplesPerPaddedSecond()) + sample) = (dedispersedData.at(second))->at((sample * observation.getNrPaddedDMs()) + dm);
}
}
}
std::fill(foldedData.begin(), foldedData.end(), static_cast< dataType >(0));
std::fill(foldedData_c.begin(), foldedData_c.end(), static_cast< dataType >(0));
std::fill(counters_c.begin(), counters_c.end(), 0);
std::fill(readCounters.begin(), readCounters.end(), 0);
std::fill(writeCounters.begin(), writeCounters.end(), 0);
// Copy data structures to device
try {
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(samplesPerBin_d, CL_FALSE, 0, samplesPerBin->size() * sizeof(unsigned int), reinterpret_cast< void * >(samplesPerBin->data()));
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(foldedData_d, CL_FALSE, 0, foldedData.size() * sizeof(dataType), reinterpret_cast< void * >(foldedData.data()));
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(readCounters_d, CL_FALSE, 0, readCounters.size() * sizeof(unsigned int), reinterpret_cast< void * >(readCounters.data()));
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(writeCounters_d, CL_FALSE, 0, writeCounters.size() * sizeof(unsigned int), reinterpret_cast< void * >(writeCounters.data()));
} catch ( cl::Error &err ) {
std::cerr << "OpenCL error H2D transfer: " << isa::utils::toString< cl_int >(err.err()) << "." << std::endl;
return 1;
}
// Generate kernel
cl::Kernel * kernel;
std::string * code = PulsarSearch::getFoldingOpenCL(nrDMsPerBlock, nrPeriodsPerBlock, nrBinsPerBlock, nrDMsPerThread, nrPeriodsPerThread, nrBinsPerThread, typeName, observation);
if ( print ) {
std::cout << *code << std::endl;
}
try {
kernel = isa::OpenCL::compile("folding", *code, "-cl-mad-enable -Werror", *clContext, clDevices->at(clDeviceID));
} catch ( isa::Exceptions::OpenCLError &err ) {
std::cerr << err.what() << std::endl;
return 1;
}
// Run OpenCL kernel and CPU control
try {
cl::NDRange global(observation.getNrPaddedDMs() / nrDMsPerThread, observation.getNrPeriods() / nrPeriodsPerThread, observation.getNrBins() / nrBinsPerThread);
cl::NDRange local(nrDMsPerBlock, nrPeriodsPerBlock, nrBinsPerBlock);
kernel->setArg(1, dedispersedData_d);
kernel->setArg(2, foldedData_d);
kernel->setArg(5, samplesPerBin_d);
for ( unsigned int second = 0; second < observation.getNrSeconds(); second++ ) {
kernel->setArg(0, second);
if ( second % 2 == 0 ) {
kernel->setArg(3, readCounters_d);
kernel->setArg(4, writeCounters_d);
} else {
kernel->setArg(3, writeCounters_d);
kernel->setArg(4, readCounters_d);
}
clQueues->at(clDeviceID)[0].enqueueWriteBuffer(dedispersedData_d, CL_FALSE, 0, (dedispersedData.at(second))->size() * sizeof(dataType), reinterpret_cast< void * >((dedispersedData.at(second))->data()));
clQueues->at(clDeviceID)[0].enqueueNDRangeKernel(*kernel, cl::NullRange, global, local);
PulsarSearch::folding(second, observation, *(dedispersedData_c.at(second)), foldedData_c, counters_c);
}
clQueues->at(clDeviceID)[0].enqueueReadBuffer(foldedData_d, CL_TRUE, 0, foldedData.size() * sizeof(dataType), reinterpret_cast< void * >(foldedData.data()));
} catch ( cl::Error &err ) {
std::cerr << "OpenCL error: " << isa::utils::toString< cl_int >(err.err()) << "." << std::endl;
return 1;
}
for ( unsigned int dm = 0; dm < observation.getNrDMs(); dm++ ) {
for ( unsigned int period = 0; period < observation.getNrPeriods(); period++ ) {
for ( unsigned int bin = 0; bin < observation.getNrBins(); bin++ ) {
if ( ! isa::utils::same(foldedData_c[(dm * observation.getNrPeriods() * observation.getNrPaddedBins()) + (period * observation.getNrPaddedBins()) + bin], foldedData[(bin * observation.getNrPeriods() * observation.getNrPaddedDMs()) * (period * observation.getNrPaddedDMs()) + dm]) ) {
wrongSamples++;
}
}
}
}
if ( wrongSamples > 0 ) {
std::cout << "Wrong samples: " << wrongSamples << " (" << (wrongSamples * 100.0) / (static_cast< long long unsigned int >(observation.getNrDMs()) * observation.getNrPeriods() * observation.getNrBins()) << "%)." << std::endl;
} else {
std::cout << "TEST PASSED." << std::endl;
}
return 0;
}
<|endoftext|> |
<commit_before>/*
* The MIT License (MIT)
*
* Copyright (c) 2014 Pavel Strakhov
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*
*/
#include "ToolWindowManagerArea.h"
#include "ToolWindowManagerTabBar.h"
#include "ToolWindowManager.h"
#include <QApplication>
#include <QMouseEvent>
#include <QDebug>
#include <algorithm>
static void showCloseButton(QTabBar *bar, int index, bool show) {
QWidget *button = bar->tabButton(index, QTabBar::RightSide);
if(button == NULL)
button = bar->tabButton(index, QTabBar::LeftSide);
if(button)
button->resize(show ? QSize(16, 16) : QSize(0, 0));
}
ToolWindowManagerArea::ToolWindowManagerArea(ToolWindowManager *manager, QWidget *parent) :
QTabWidget(parent)
, m_manager(manager)
{
m_tabBar = new ToolWindowManagerTabBar(this);
setTabBar(m_tabBar);
m_tabBar->setTabsClosable(true);
m_dragCanStart = false;
m_tabDragCanStart = false;
m_inTabMoved = false;
m_userCanDrop = true;
setMovable(true);
setDocumentMode(true);
tabBar()->installEventFilter(this);
m_manager->m_areas << this;
QObject::connect(tabBar(), &QTabBar::tabMoved, this, &ToolWindowManagerArea::tabMoved);
QObject::connect(tabBar(), &QTabBar::tabCloseRequested, this, &ToolWindowManagerArea::tabClosing);
QObject::connect(this, &QTabWidget::currentChanged, this, &ToolWindowManagerArea::tabSelected);
}
ToolWindowManagerArea::~ToolWindowManagerArea() {
m_manager->m_areas.removeOne(this);
}
void ToolWindowManagerArea::addToolWindow(QWidget *toolWindow) {
addToolWindows(QList<QWidget*>() << toolWindow);
}
void ToolWindowManagerArea::addToolWindows(const QList<QWidget *> &toolWindows) {
int index = 0;
foreach(QWidget* toolWindow, toolWindows) {
index = addTab(toolWindow, toolWindow->windowIcon(), toolWindow->windowTitle());
if(m_manager->toolWindowProperties(toolWindow) & ToolWindowManager::HideCloseButton) {
showCloseButton(tabBar(), index, false);
}
}
setCurrentIndex(index);
m_manager->m_lastUsedArea = this;
}
QList<QWidget *> ToolWindowManagerArea::toolWindows() {
QList<QWidget *> result;
for(int i = 0; i < count(); i++) {
result << widget(i);
}
return result;
}
void ToolWindowManagerArea::updateToolWindow(QWidget* toolWindow) {
int index = indexOf(toolWindow);
if(index >= 0) {
if(m_manager->toolWindowProperties(toolWindow) & ToolWindowManager::HideCloseButton) {
showCloseButton(tabBar(), index, false);
} else {
showCloseButton(tabBar(), index, true);
}
tabBar()->setTabText(index, toolWindow->windowTitle());
}
}
void ToolWindowManagerArea::mousePressEvent(QMouseEvent *) {
if (qApp->mouseButtons() == Qt::LeftButton) {
m_dragCanStart = true;
}
}
void ToolWindowManagerArea::mouseReleaseEvent(QMouseEvent *) {
m_dragCanStart = false;
m_manager->updateDragPosition();
}
void ToolWindowManagerArea::mouseMoveEvent(QMouseEvent *) {
check_mouse_move();
}
bool ToolWindowManagerArea::eventFilter(QObject *object, QEvent *event) {
if (object == tabBar()) {
if (event->type() == QEvent::MouseButtonPress &&
qApp->mouseButtons() == Qt::LeftButton) {
QPoint pos = static_cast<QMouseEvent*>(event)->pos();
int tabIndex = tabBar()->tabAt(pos);
// can start tab drag only if mouse is at some tab, not at empty tabbar space
if (tabIndex >= 0) {
m_tabDragCanStart = true;
if (m_manager->toolWindowProperties(widget(tabIndex)) & ToolWindowManager::DisableDraggableTab) {
setMovable(false);
} else {
setMovable(true);
}
} else if (m_tabBar == NULL || !m_tabBar->inButton(pos)) {
m_dragCanStart = true;
}
} else if (event->type() == QEvent::MouseButtonPress &&
qApp->mouseButtons() == Qt::MiddleButton) {
int tabIndex = tabBar()->tabAt(static_cast<QMouseEvent*>(event)->pos());
if(tabIndex >= 0) {
QWidget *w = widget(tabIndex);
if(!(m_manager->toolWindowProperties(w) & ToolWindowManager::HideCloseButton)) {
m_manager->removeToolWindow(w);
}
}
} else if (event->type() == QEvent::MouseButtonRelease) {
m_tabDragCanStart = false;
m_dragCanStart = false;
m_manager->updateDragPosition();
} else if (event->type() == QEvent::MouseMove) {
m_manager->updateDragPosition();
if (m_tabDragCanStart) {
if (tabBar()->rect().contains(static_cast<QMouseEvent*>(event)->pos())) {
return false;
}
if (qApp->mouseButtons() != Qt::LeftButton) {
return false;
}
QWidget* toolWindow = currentWidget();
if (!toolWindow || !m_manager->m_toolWindows.contains(toolWindow)) {
return false;
}
m_tabDragCanStart = false;
//stop internal tab drag in QTabBar
QMouseEvent* releaseEvent = new QMouseEvent(QEvent::MouseButtonRelease,
static_cast<QMouseEvent*>(event)->pos(),
Qt::LeftButton, Qt::LeftButton, 0);
qApp->sendEvent(tabBar(), releaseEvent);
m_manager->startDrag(QList<QWidget*>() << toolWindow, NULL);
} else if (m_dragCanStart) {
check_mouse_move();
}
}
}
return QTabWidget::eventFilter(object, event);
}
void ToolWindowManagerArea::tabInserted(int index) {
// update the select order. Increment any existing index after the insertion point to keep the
// indices in the list up to date.
for (int &idx : m_tabSelectOrder) {
if (idx >= index)
idx++;
}
// if the tab inserted is the current index (most likely) then add it at the end, otherwise
// add it next-to-end (to keep the most recent tab the same).
if (currentIndex() == index || m_tabSelectOrder.isEmpty())
m_tabSelectOrder.append(index);
else
m_tabSelectOrder.insert(m_tabSelectOrder.count()-1, index);
QTabWidget::tabInserted(index);
}
void ToolWindowManagerArea::tabRemoved(int index) {
// update the select order. Remove the index that just got deleted, and decrement any index
// greater than it to remap to their new indices
m_tabSelectOrder.removeOne(index);
for (int &idx : m_tabSelectOrder) {
if (idx > index)
idx--;
}
QTabWidget::tabRemoved(index);
}
void ToolWindowManagerArea::tabSelected(int index) {
// move this tab to the end of the select order, as long as we have it - if it's a new index then
// ignore and leave it to be handled in tabInserted()
if (m_tabSelectOrder.contains(index)) {
m_tabSelectOrder.removeOne(index);
m_tabSelectOrder.append(index);
}
}
void ToolWindowManagerArea::tabClosing(int index) {
// before closing this index, switch the current index to the next tab in succession.
// should never get here but let's check this
if (m_tabSelectOrder.isEmpty())
return;
// when closing the last tab there's nothing to do
if (m_tabSelectOrder.count() == 1)
return;
// if the last in the select order is being closed, switch to the next most selected tab
if (m_tabSelectOrder.last() == index)
setCurrentIndex(m_tabSelectOrder.at(m_tabSelectOrder.count()-2));
}
QVariantMap ToolWindowManagerArea::saveState() {
QVariantMap result;
result[QStringLiteral("type")] = QStringLiteral("area");
result[QStringLiteral("currentIndex")] = currentIndex();
QVariantList objects;
objects.reserve(count());
for(int i = 0; i < count(); i++) {
QWidget *w = widget(i);
QString name = w->objectName();
if (name.isEmpty()) {
qWarning("cannot save state of tool window without object name");
} else {
QVariantMap objectData;
objectData[QStringLiteral("name")] = name;
objectData[QStringLiteral("data")] = w->property("persistData");
objects.push_back(objectData);
}
}
result[QStringLiteral("objects")] = objects;
return result;
}
void ToolWindowManagerArea::restoreState(const QVariantMap &savedData) {
for(QVariant object : savedData[QStringLiteral("objects")].toList()) {
QVariantMap objectData = object.toMap();
if (objectData.isEmpty()) { continue; }
QString objectName = objectData[QStringLiteral("name")].toString();
if (objectName.isEmpty()) { continue; }
QWidget *t = NULL;
for(QWidget* toolWindow : m_manager->m_toolWindows) {
if (toolWindow->objectName() == objectName) {
t = toolWindow;
break;
}
}
if (t == NULL) t = m_manager->createToolWindow(objectName);
if (t) {
t->setProperty("persistData", objectData[QStringLiteral("data")]);
addToolWindow(t);
} else {
qWarning("tool window with name '%s' not found or created", objectName.toLocal8Bit().constData());
}
}
setCurrentIndex(savedData[QStringLiteral("currentIndex")].toInt());
}
void ToolWindowManagerArea::check_mouse_move() {
m_manager->updateDragPosition();
if (qApp->mouseButtons() == Qt::LeftButton &&
!rect().contains(mapFromGlobal(QCursor::pos())) &&
m_dragCanStart) {
m_dragCanStart = false;
QList<QWidget*> toolWindows;
for(int i = 0; i < count(); i++) {
QWidget* toolWindow = widget(i);
if (!m_manager->m_toolWindows.contains(toolWindow)) {
qWarning("tab widget contains unmanaged widget");
} else {
toolWindows << toolWindow;
}
}
m_manager->startDrag(toolWindows, NULL);
}
}
void ToolWindowManagerArea::tabMoved(int from, int to) {
if(m_inTabMoved) return;
// update the select order.
// This amounts to just a swap - any indices other than the pair in question are unaffected since
// one tab is removed (above/below) and added (below/above) so the indices themselves remain the
// same.
for (int &idx : m_tabSelectOrder) {
if (idx == from)
idx = to;
else if (idx == to)
idx = from;
}
QWidget *a = widget(from);
QWidget *b = widget(to);
if(!a || !b) return;
if(m_manager->toolWindowProperties(a) & ToolWindowManager::DisableDraggableTab ||
m_manager->toolWindowProperties(b) & ToolWindowManager::DisableDraggableTab)
{
m_inTabMoved = true;
tabBar()->moveTab(to, from);
m_inTabMoved = false;
}
}
<commit_msg>Fix missing handling for tab close buttons<commit_after>/*
* The MIT License (MIT)
*
* Copyright (c) 2014 Pavel Strakhov
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*
*/
#include "ToolWindowManagerArea.h"
#include "ToolWindowManagerTabBar.h"
#include "ToolWindowManager.h"
#include <QApplication>
#include <QMouseEvent>
#include <QDebug>
#include <algorithm>
static void showCloseButton(QTabBar *bar, int index, bool show) {
QWidget *button = bar->tabButton(index, QTabBar::RightSide);
if(button == NULL)
button = bar->tabButton(index, QTabBar::LeftSide);
if(button)
button->resize(show ? QSize(16, 16) : QSize(0, 0));
}
ToolWindowManagerArea::ToolWindowManagerArea(ToolWindowManager *manager, QWidget *parent) :
QTabWidget(parent)
, m_manager(manager)
{
m_tabBar = new ToolWindowManagerTabBar(this);
setTabBar(m_tabBar);
m_tabBar->setTabsClosable(true);
m_dragCanStart = false;
m_tabDragCanStart = false;
m_inTabMoved = false;
m_userCanDrop = true;
setMovable(true);
setDocumentMode(true);
tabBar()->installEventFilter(this);
m_manager->m_areas << this;
QObject::connect(tabBar(), &QTabBar::tabMoved, this, &ToolWindowManagerArea::tabMoved);
QObject::connect(tabBar(), &QTabBar::tabCloseRequested, this, &ToolWindowManagerArea::tabClosing);
QObject::connect(tabBar(), &QTabBar::tabCloseRequested, this, &QTabWidget::tabCloseRequested);
QObject::connect(this, &QTabWidget::currentChanged, this, &ToolWindowManagerArea::tabSelected);
}
ToolWindowManagerArea::~ToolWindowManagerArea() {
m_manager->m_areas.removeOne(this);
}
void ToolWindowManagerArea::addToolWindow(QWidget *toolWindow) {
addToolWindows(QList<QWidget*>() << toolWindow);
}
void ToolWindowManagerArea::addToolWindows(const QList<QWidget *> &toolWindows) {
int index = 0;
foreach(QWidget* toolWindow, toolWindows) {
index = addTab(toolWindow, toolWindow->windowIcon(), toolWindow->windowTitle());
if(m_manager->toolWindowProperties(toolWindow) & ToolWindowManager::HideCloseButton) {
showCloseButton(tabBar(), index, false);
}
}
setCurrentIndex(index);
m_manager->m_lastUsedArea = this;
}
QList<QWidget *> ToolWindowManagerArea::toolWindows() {
QList<QWidget *> result;
for(int i = 0; i < count(); i++) {
result << widget(i);
}
return result;
}
void ToolWindowManagerArea::updateToolWindow(QWidget* toolWindow) {
int index = indexOf(toolWindow);
if(index >= 0) {
if(m_manager->toolWindowProperties(toolWindow) & ToolWindowManager::HideCloseButton) {
showCloseButton(tabBar(), index, false);
} else {
showCloseButton(tabBar(), index, true);
}
tabBar()->setTabText(index, toolWindow->windowTitle());
}
}
void ToolWindowManagerArea::mousePressEvent(QMouseEvent *) {
if (qApp->mouseButtons() == Qt::LeftButton) {
m_dragCanStart = true;
}
}
void ToolWindowManagerArea::mouseReleaseEvent(QMouseEvent *) {
m_dragCanStart = false;
m_manager->updateDragPosition();
}
void ToolWindowManagerArea::mouseMoveEvent(QMouseEvent *) {
check_mouse_move();
}
bool ToolWindowManagerArea::eventFilter(QObject *object, QEvent *event) {
if (object == tabBar()) {
if (event->type() == QEvent::MouseButtonPress &&
qApp->mouseButtons() == Qt::LeftButton) {
QPoint pos = static_cast<QMouseEvent*>(event)->pos();
int tabIndex = tabBar()->tabAt(pos);
// can start tab drag only if mouse is at some tab, not at empty tabbar space
if (tabIndex >= 0) {
m_tabDragCanStart = true;
if (m_manager->toolWindowProperties(widget(tabIndex)) & ToolWindowManager::DisableDraggableTab) {
setMovable(false);
} else {
setMovable(true);
}
} else if (m_tabBar == NULL || !m_tabBar->inButton(pos)) {
m_dragCanStart = true;
}
} else if (event->type() == QEvent::MouseButtonPress &&
qApp->mouseButtons() == Qt::MiddleButton) {
int tabIndex = tabBar()->tabAt(static_cast<QMouseEvent*>(event)->pos());
if(tabIndex >= 0) {
QWidget *w = widget(tabIndex);
if(!(m_manager->toolWindowProperties(w) & ToolWindowManager::HideCloseButton)) {
m_manager->removeToolWindow(w);
}
}
} else if (event->type() == QEvent::MouseButtonRelease) {
m_tabDragCanStart = false;
m_dragCanStart = false;
m_manager->updateDragPosition();
} else if (event->type() == QEvent::MouseMove) {
m_manager->updateDragPosition();
if (m_tabDragCanStart) {
if (tabBar()->rect().contains(static_cast<QMouseEvent*>(event)->pos())) {
return false;
}
if (qApp->mouseButtons() != Qt::LeftButton) {
return false;
}
QWidget* toolWindow = currentWidget();
if (!toolWindow || !m_manager->m_toolWindows.contains(toolWindow)) {
return false;
}
m_tabDragCanStart = false;
//stop internal tab drag in QTabBar
QMouseEvent* releaseEvent = new QMouseEvent(QEvent::MouseButtonRelease,
static_cast<QMouseEvent*>(event)->pos(),
Qt::LeftButton, Qt::LeftButton, 0);
qApp->sendEvent(tabBar(), releaseEvent);
m_manager->startDrag(QList<QWidget*>() << toolWindow, NULL);
} else if (m_dragCanStart) {
check_mouse_move();
}
}
}
return QTabWidget::eventFilter(object, event);
}
void ToolWindowManagerArea::tabInserted(int index) {
// update the select order. Increment any existing index after the insertion point to keep the
// indices in the list up to date.
for (int &idx : m_tabSelectOrder) {
if (idx >= index)
idx++;
}
// if the tab inserted is the current index (most likely) then add it at the end, otherwise
// add it next-to-end (to keep the most recent tab the same).
if (currentIndex() == index || m_tabSelectOrder.isEmpty())
m_tabSelectOrder.append(index);
else
m_tabSelectOrder.insert(m_tabSelectOrder.count()-1, index);
QTabWidget::tabInserted(index);
}
void ToolWindowManagerArea::tabRemoved(int index) {
// update the select order. Remove the index that just got deleted, and decrement any index
// greater than it to remap to their new indices
m_tabSelectOrder.removeOne(index);
for (int &idx : m_tabSelectOrder) {
if (idx > index)
idx--;
}
QTabWidget::tabRemoved(index);
}
void ToolWindowManagerArea::tabSelected(int index) {
// move this tab to the end of the select order, as long as we have it - if it's a new index then
// ignore and leave it to be handled in tabInserted()
if (m_tabSelectOrder.contains(index)) {
m_tabSelectOrder.removeOne(index);
m_tabSelectOrder.append(index);
}
}
void ToolWindowManagerArea::tabClosing(int index) {
// before closing this index, switch the current index to the next tab in succession.
// should never get here but let's check this
if (m_tabSelectOrder.isEmpty())
return;
// when closing the last tab there's nothing to do
if (m_tabSelectOrder.count() == 1)
return;
// if the last in the select order is being closed, switch to the next most selected tab
if (m_tabSelectOrder.last() == index)
setCurrentIndex(m_tabSelectOrder.at(m_tabSelectOrder.count()-2));
}
QVariantMap ToolWindowManagerArea::saveState() {
QVariantMap result;
result[QStringLiteral("type")] = QStringLiteral("area");
result[QStringLiteral("currentIndex")] = currentIndex();
QVariantList objects;
objects.reserve(count());
for(int i = 0; i < count(); i++) {
QWidget *w = widget(i);
QString name = w->objectName();
if (name.isEmpty()) {
qWarning("cannot save state of tool window without object name");
} else {
QVariantMap objectData;
objectData[QStringLiteral("name")] = name;
objectData[QStringLiteral("data")] = w->property("persistData");
objects.push_back(objectData);
}
}
result[QStringLiteral("objects")] = objects;
return result;
}
void ToolWindowManagerArea::restoreState(const QVariantMap &savedData) {
for(QVariant object : savedData[QStringLiteral("objects")].toList()) {
QVariantMap objectData = object.toMap();
if (objectData.isEmpty()) { continue; }
QString objectName = objectData[QStringLiteral("name")].toString();
if (objectName.isEmpty()) { continue; }
QWidget *t = NULL;
for(QWidget* toolWindow : m_manager->m_toolWindows) {
if (toolWindow->objectName() == objectName) {
t = toolWindow;
break;
}
}
if (t == NULL) t = m_manager->createToolWindow(objectName);
if (t) {
t->setProperty("persistData", objectData[QStringLiteral("data")]);
addToolWindow(t);
} else {
qWarning("tool window with name '%s' not found or created", objectName.toLocal8Bit().constData());
}
}
setCurrentIndex(savedData[QStringLiteral("currentIndex")].toInt());
}
void ToolWindowManagerArea::check_mouse_move() {
m_manager->updateDragPosition();
if (qApp->mouseButtons() == Qt::LeftButton &&
!rect().contains(mapFromGlobal(QCursor::pos())) &&
m_dragCanStart) {
m_dragCanStart = false;
QList<QWidget*> toolWindows;
for(int i = 0; i < count(); i++) {
QWidget* toolWindow = widget(i);
if (!m_manager->m_toolWindows.contains(toolWindow)) {
qWarning("tab widget contains unmanaged widget");
} else {
toolWindows << toolWindow;
}
}
m_manager->startDrag(toolWindows, NULL);
}
}
void ToolWindowManagerArea::tabMoved(int from, int to) {
if(m_inTabMoved) return;
// update the select order.
// This amounts to just a swap - any indices other than the pair in question are unaffected since
// one tab is removed (above/below) and added (below/above) so the indices themselves remain the
// same.
for (int &idx : m_tabSelectOrder) {
if (idx == from)
idx = to;
else if (idx == to)
idx = from;
}
QWidget *a = widget(from);
QWidget *b = widget(to);
if(!a || !b) return;
if(m_manager->toolWindowProperties(a) & ToolWindowManager::DisableDraggableTab ||
m_manager->toolWindowProperties(b) & ToolWindowManager::DisableDraggableTab)
{
m_inTabMoved = true;
tabBar()->moveTab(to, from);
m_inTabMoved = false;
}
}
<|endoftext|> |
<commit_before>#include "Utility/Configuration.h"
#include <iostream>
#include <fstream>
#include <string>
#include <map>
#include <vector>
#include <stdexcept>
#include <algorithm>
#include "Utility/String.h"
Configuration::Configuration(const std::string& file_name)
{
std::ifstream ifs(file_name);
if( ! ifs)
{
throw std::runtime_error("Could not open configuration file: " + file_name);
}
for(std::string line; std::getline(ifs, line);)
{
line = String::strip_comments(line, "#");
if(line.empty())
{
continue;
}
if( ! String::contains(line, '='))
{
throw std::runtime_error("Configuration file lines must be of form \"Name = Value\"\n" + line);
}
const auto line_split = String::split(line, "=", 1);
const auto parameter = standardize_text(line_split[0]);
const auto value = String::trim_outer_whitespace(line_split[1]);
if(value.empty())
{
throw std::runtime_error("Configuration parameter cannot be empty.\n" + line);
}
if(parameters.count(parameter) > 0)
{
throw std::runtime_error("Configuration parameter used more than once: " + parameter);
}
parameters[parameter] = value;
used[parameter] = false;
}
}
std::string Configuration::as_text(const std::string& parameter) const
{
try
{
const auto key = standardize_text(parameter);
used.at(key) = true;
return parameters.at(key);
}
catch(const std::out_of_range&)
{
for(const auto& [key, value] : parameters)
{
std::cerr << "\"" << key << "\" --> \"" << value << "\"" << std::endl;
}
throw std::runtime_error("Configuration parameter not found: " + parameter);
}
}
bool Configuration::as_boolean(const std::string& parameter, const std::string& affirmative, const std::string& negative) const
{
const auto response = standardize_text(as_text(parameter));
if(response == standardize_text(affirmative))
{
return true;
}
else if(response == standardize_text(negative))
{
return false;
}
else
{
throw std::runtime_error("Invalid value for \"" + parameter + "\" : \"" + as_text(parameter) + "\"" +
"\nExpected \"" + affirmative + "\" or \"" + negative + "\".");
}
}
bool Configuration::has_parameter(const std::string& parameter) const noexcept
{
return parameters.count(standardize_text(parameter)) > 0;
}
std::string Configuration::standardize_text(const std::string& input) noexcept
{
return String::lowercase(String::remove_extra_whitespace(input));
}
void Configuration::print_unused_parameters() const noexcept
{
for(const auto& [param, value] : parameters)
{
if( ! used[param])
{
std::cout << param << " --> " << value << std::endl;
}
}
}
bool Configuration::any_unused_parameters() const noexcept
{
return std::any_of(used.begin(), used.end(), [](const auto& key_value) { return ! key_value.second; });
}
<commit_msg>Add blank line<commit_after>#include "Utility/Configuration.h"
#include <iostream>
#include <fstream>
#include <string>
#include <map>
#include <vector>
#include <stdexcept>
#include <algorithm>
#include "Utility/String.h"
Configuration::Configuration(const std::string& file_name)
{
std::ifstream ifs(file_name);
if( ! ifs)
{
throw std::runtime_error("Could not open configuration file: " + file_name);
}
for(std::string line; std::getline(ifs, line);)
{
line = String::strip_comments(line, "#");
if(line.empty())
{
continue;
}
if( ! String::contains(line, '='))
{
throw std::runtime_error("Configuration file lines must be of form \"Name = Value\"\n" + line);
}
const auto line_split = String::split(line, "=", 1);
const auto parameter = standardize_text(line_split[0]);
const auto value = String::trim_outer_whitespace(line_split[1]);
if(value.empty())
{
throw std::runtime_error("Configuration parameter cannot be empty.\n" + line);
}
if(parameters.count(parameter) > 0)
{
throw std::runtime_error("Configuration parameter used more than once: " + parameter);
}
parameters[parameter] = value;
used[parameter] = false;
}
}
std::string Configuration::as_text(const std::string& parameter) const
{
try
{
const auto key = standardize_text(parameter);
used.at(key) = true;
return parameters.at(key);
}
catch(const std::out_of_range&)
{
for(const auto& [key, value] : parameters)
{
std::cerr << "\"" << key << "\" --> \"" << value << "\"" << std::endl;
}
throw std::runtime_error("Configuration parameter not found: " + parameter);
}
}
bool Configuration::as_boolean(const std::string& parameter, const std::string& affirmative, const std::string& negative) const
{
const auto response = standardize_text(as_text(parameter));
if(response == standardize_text(affirmative))
{
return true;
}
else if(response == standardize_text(negative))
{
return false;
}
else
{
throw std::runtime_error("Invalid value for \"" + parameter + "\" : \"" + as_text(parameter) + "\"" +
"\nExpected \"" + affirmative + "\" or \"" + negative + "\".");
}
}
bool Configuration::has_parameter(const std::string& parameter) const noexcept
{
return parameters.count(standardize_text(parameter)) > 0;
}
std::string Configuration::standardize_text(const std::string& input) noexcept
{
return String::lowercase(String::remove_extra_whitespace(input));
}
void Configuration::print_unused_parameters() const noexcept
{
for(const auto& [param, value] : parameters)
{
if( ! used[param])
{
std::cout << param << " --> " << value << std::endl;
}
}
}
bool Configuration::any_unused_parameters() const noexcept
{
return std::any_of(used.begin(), used.end(), [](const auto& key_value) { return ! key_value.second; });
}
<|endoftext|> |
<commit_before>// A try to port libgit2 status.c example to libqgit2
#include <QCoreApplication>
#include <QTimer>
#include <iostream>
#include <bitset>
#include "qgitrepository.h"
#include "qgitstatuslist.h"
#include "qgitstatusentry.h"
#include "qgitstatus.h"
#include "qgitstatusoptions.h"
#include "QStatus.h"
using namespace LibQGit2;
QStatus::QStatus()
{
// Create a new repository object
Repository * repo = new LibQGit2::Repository();
// Open a local fixed path
repo->open(QString("/home/leo/projects/libqgit2"));
QGitStatusOptions *opt = new QGitStatusOptions;
opt->setShowFlags(QGitStatusOptions::ShowIndexAndWorkdir);
opt->setStatusFlags(QGitStatusOptions::IncludeUnmodified | QGitStatusOptions::IncludeUntracked |
QGitStatusOptions::RenamesHeadToIndex | QGitStatusOptions::RenamesIdexToWorkdir
);
// Get the list of status entries
QGitStatusList status_list = repo->status(opt);
// Count entries
size_t entries = status_list.entryCount();
for (size_t i = 0; i < entries; ++i) {
const QGitStatusEntry entry = status_list.entryByIndex(i);
if (entry.status().isCurrent()) {
std::cout << "C";
} else {
std::cout << " ";
}
if (entry.status().isNewInIndex()) {
std::cout << "N";
} else {
std::cout << " ";
}
if (entry.status().isModifiedInIndex()) {
std::cout << "M";
} else {
std::cout << " ";
}
if (entry.status().isDeletedInIndex()) {
std::cout << "D";
} else {
std::cout << " ";
}
if (entry.status().isRenamedInIndex()) {
std::cout << "R";
} else {
std::cout << " ";
}
if (entry.status().isTypeChangedInIndex()) {
std::cout << "T";
} else {
std::cout << " ";
}
std::cout << " ";
if (entry.status().isNewInWorkdir()) {
std::cout << "N";
} else {
std::cout << " ";
}
if (entry.status().isModifiedInWorkdir()) {
std::cout << "M";
} else {
std::cout << " ";
}
if (entry.status().isDeletedInWorkdir()) {
std::cout << "D";
} else {
std::cout << " ";
}
if (entry.status().isRenamedInWorkdir()) {
std::cout << "R";
} else {
std::cout << " ";
}
if (entry.status().isTypeChangedInWorkdir()) {
std::cout << "T";
} else {
std::cout << " ";
}
std::cout << " ";
std::cout << entry.path().toStdString() << std::endl;
// std::bitset<16> x(entry.status().data());
}
}
QStatus::~QStatus()
{}
#include "QStatus.moc"
int main(int argc, char** argv)
{
QCoreApplication app(argc, argv);
QStatus foo;
return app.exec();
}
<commit_msg>QGitStatusEntry -> StatusEntry<commit_after>// A try to port libgit2 status.c example to libqgit2
#include <QCoreApplication>
#include <QTimer>
#include <iostream>
#include <bitset>
#include "qgitrepository.h"
#include "qgitstatuslist.h"
#include "qgitstatusentry.h"
#include "qgitstatus.h"
#include "qgitstatusoptions.h"
#include "QStatus.h"
using namespace LibQGit2;
QStatus::QStatus()
{
// Create a new repository object
Repository * repo = new LibQGit2::Repository();
// Open a local fixed path
repo->open(QString("/home/leo/projects/libqgit2"));
QGitStatusOptions *opt = new QGitStatusOptions;
opt->setShowFlags(QGitStatusOptions::ShowIndexAndWorkdir);
opt->setStatusFlags(QGitStatusOptions::IncludeUnmodified | QGitStatusOptions::IncludeUntracked |
QGitStatusOptions::RenamesHeadToIndex | QGitStatusOptions::RenamesIdexToWorkdir
);
// Get the list of status entries
QGitStatusList status_list = repo->status(opt);
// Count entries
size_t entries = status_list.entryCount();
for (size_t i = 0; i < entries; ++i) {
const StatusEntry entry = status_list.entryByIndex(i);
if (entry.status().isCurrent()) {
std::cout << "C";
} else {
std::cout << " ";
}
if (entry.status().isNewInIndex()) {
std::cout << "N";
} else {
std::cout << " ";
}
if (entry.status().isModifiedInIndex()) {
std::cout << "M";
} else {
std::cout << " ";
}
if (entry.status().isDeletedInIndex()) {
std::cout << "D";
} else {
std::cout << " ";
}
if (entry.status().isRenamedInIndex()) {
std::cout << "R";
} else {
std::cout << " ";
}
if (entry.status().isTypeChangedInIndex()) {
std::cout << "T";
} else {
std::cout << " ";
}
std::cout << " ";
if (entry.status().isNewInWorkdir()) {
std::cout << "N";
} else {
std::cout << " ";
}
if (entry.status().isModifiedInWorkdir()) {
std::cout << "M";
} else {
std::cout << " ";
}
if (entry.status().isDeletedInWorkdir()) {
std::cout << "D";
} else {
std::cout << " ";
}
if (entry.status().isRenamedInWorkdir()) {
std::cout << "R";
} else {
std::cout << " ";
}
if (entry.status().isTypeChangedInWorkdir()) {
std::cout << "T";
} else {
std::cout << " ";
}
std::cout << " ";
std::cout << entry.path().toStdString() << std::endl;
// std::bitset<16> x(entry.status().data());
}
}
QStatus::~QStatus()
{}
#include "QStatus.moc"
int main(int argc, char** argv)
{
QCoreApplication app(argc, argv);
QStatus foo;
return app.exec();
}
<|endoftext|> |
<commit_before>/* -*- Mode: C++; tab-width: 4; indent-tabs-mode: nil; c-basic-offset: 4 -*- */
/*
* This file is part of the LibreOffice project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* This file incorporates work covered by the following license notice:
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed
* with this work for additional information regarding copyright
* ownership. The ASF licenses this file to you under the Apache
* License, Version 2.0 (the "License"); you may not use this file
* except in compliance with the License. You may obtain a copy of
* the License at http://www.apache.org/licenses/LICENSE-2.0 .
*/
#ifndef INCLUDED_FILTER_SOURCE_XMLFILTERADAPTOR_XMLFILTERADAPTOR_HXX
#define INCLUDED_FILTER_SOURCE_XMLFILTERADAPTOR_XMLFILTERADAPTOR_HXX
#include <com/sun/star/document/XFilter.hpp>
#include <com/sun/star/document/XExporter.hpp>
#include <com/sun/star/document/XImporter.hpp>
#include <com/sun/star/lang/XInitialization.hpp>
#include <com/sun/star/lang/XServiceInfo.hpp>
#include <com/sun/star/uno/XComponentContext.hpp>
#include <cppuhelper/implbase5.hxx>
enum FilterType
{
FILTER_IMPORT,
FILTER_EXPORT
};
/* This component will be instantiated for both import or export. Whether it calls
* setSourceDocument or setTargetDocument determines which Impl function the filter
* member calls */
class XmlFilterAdaptor : public cppu::WeakImplHelper5
<
com::sun::star::document::XFilter,
com::sun::star::document::XExporter,
com::sun::star::document::XImporter,
com::sun::star::lang::XInitialization,
com::sun::star::lang::XServiceInfo
>
{
protected:
::com::sun::star::uno::Reference< ::com::sun::star::uno::XComponentContext > mxContext;
::com::sun::star::uno::Reference< ::com::sun::star::lang::XComponent > mxDoc;
OUString msFilterName;
::com::sun::star::uno::Sequence< OUString > msUserData;
OUString msTemplateName;
FilterType meType;
sal_Bool SAL_CALL exportImpl( const ::com::sun::star::uno::Sequence< ::com::sun::star::beans::PropertyValue >& aDescriptor )
throw (::com::sun::star::uno::RuntimeException);
sal_Bool SAL_CALL importImpl( const ::com::sun::star::uno::Sequence< ::com::sun::star::beans::PropertyValue >& aDescriptor )
throw (::com::sun::star::uno::RuntimeException);
public:
XmlFilterAdaptor( const ::com::sun::star::uno::Reference< ::com::sun::star::uno::XComponentContext > & rxContext)
: mxContext( rxContext ) {}
virtual ~XmlFilterAdaptor() {}
// XFilter
virtual sal_Bool SAL_CALL filter( const ::com::sun::star::uno::Sequence< ::com::sun::star::beans::PropertyValue >& aDescriptor )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
virtual void SAL_CALL cancel( )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XExporter
virtual void SAL_CALL setSourceDocument( const ::com::sun::star::uno::Reference< ::com::sun::star::lang::XComponent >& xDoc )
throw (::com::sun::star::lang::IllegalArgumentException, ::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XImporter
virtual void SAL_CALL setTargetDocument( const ::com::sun::star::uno::Reference< ::com::sun::star::lang::XComponent >& xDoc )
throw (::com::sun::star::lang::IllegalArgumentException, ::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XInitialization
virtual void SAL_CALL initialize( const ::com::sun::star::uno::Sequence< ::com::sun::star::uno::Any >& aArguments )
throw (::com::sun::star::uno::Exception, ::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XServiceInfo
virtual OUString SAL_CALL getImplementationName( )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
virtual sal_Bool SAL_CALL supportsService( const OUString& ServiceName )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
virtual ::com::sun::star::uno::Sequence< OUString > SAL_CALL getSupportedServiceNames( )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
};
OUString XmlFilterAdaptor_getImplementationName()
throw ( ::com::sun::star::uno::RuntimeException );
sal_Bool SAL_CALL XmlFilterAdaptor_supportsService( const OUString& ServiceName )
throw ( ::com::sun::star::uno::RuntimeException );
::com::sun::star::uno::Sequence< OUString > SAL_CALL XmlFilterAdaptor_getSupportedServiceNames( )
throw ( ::com::sun::star::uno::RuntimeException );
::com::sun::star::uno::Reference< ::com::sun::star::uno::XInterface >
SAL_CALL XmlFilterAdaptor_createInstance( const ::com::sun::star::uno::Reference< ::com::sun::star::lang::XMultiServiceFactory > & rSMgr)
throw ( ::com::sun::star::uno::Exception );
#endif
/* vim:set shiftwidth=4 softtabstop=4 expandtab: */
<commit_msg>coverity#707860 Uninitialized scalar field<commit_after>/* -*- Mode: C++; tab-width: 4; indent-tabs-mode: nil; c-basic-offset: 4 -*- */
/*
* This file is part of the LibreOffice project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* This file incorporates work covered by the following license notice:
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed
* with this work for additional information regarding copyright
* ownership. The ASF licenses this file to you under the Apache
* License, Version 2.0 (the "License"); you may not use this file
* except in compliance with the License. You may obtain a copy of
* the License at http://www.apache.org/licenses/LICENSE-2.0 .
*/
#ifndef INCLUDED_FILTER_SOURCE_XMLFILTERADAPTOR_XMLFILTERADAPTOR_HXX
#define INCLUDED_FILTER_SOURCE_XMLFILTERADAPTOR_XMLFILTERADAPTOR_HXX
#include <com/sun/star/document/XFilter.hpp>
#include <com/sun/star/document/XExporter.hpp>
#include <com/sun/star/document/XImporter.hpp>
#include <com/sun/star/lang/XInitialization.hpp>
#include <com/sun/star/lang/XServiceInfo.hpp>
#include <com/sun/star/uno/XComponentContext.hpp>
#include <cppuhelper/implbase5.hxx>
enum FilterType
{
FILTER_IMPORT,
FILTER_EXPORT
};
/* This component will be instantiated for both import or export. Whether it calls
* setSourceDocument or setTargetDocument determines which Impl function the filter
* member calls */
class XmlFilterAdaptor : public cppu::WeakImplHelper5
<
com::sun::star::document::XFilter,
com::sun::star::document::XExporter,
com::sun::star::document::XImporter,
com::sun::star::lang::XInitialization,
com::sun::star::lang::XServiceInfo
>
{
protected:
::com::sun::star::uno::Reference< ::com::sun::star::uno::XComponentContext > mxContext;
::com::sun::star::uno::Reference< ::com::sun::star::lang::XComponent > mxDoc;
OUString msFilterName;
::com::sun::star::uno::Sequence< OUString > msUserData;
OUString msTemplateName;
FilterType meType;
sal_Bool SAL_CALL exportImpl( const ::com::sun::star::uno::Sequence< ::com::sun::star::beans::PropertyValue >& aDescriptor )
throw (::com::sun::star::uno::RuntimeException);
sal_Bool SAL_CALL importImpl( const ::com::sun::star::uno::Sequence< ::com::sun::star::beans::PropertyValue >& aDescriptor )
throw (::com::sun::star::uno::RuntimeException);
public:
XmlFilterAdaptor( const ::com::sun::star::uno::Reference< ::com::sun::star::uno::XComponentContext > & rxContext)
: mxContext(rxContext)
, meType(FILTER_IMPORT)
{
}
virtual ~XmlFilterAdaptor() {}
// XFilter
virtual sal_Bool SAL_CALL filter( const ::com::sun::star::uno::Sequence< ::com::sun::star::beans::PropertyValue >& aDescriptor )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
virtual void SAL_CALL cancel( )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XExporter
virtual void SAL_CALL setSourceDocument( const ::com::sun::star::uno::Reference< ::com::sun::star::lang::XComponent >& xDoc )
throw (::com::sun::star::lang::IllegalArgumentException, ::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XImporter
virtual void SAL_CALL setTargetDocument( const ::com::sun::star::uno::Reference< ::com::sun::star::lang::XComponent >& xDoc )
throw (::com::sun::star::lang::IllegalArgumentException, ::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XInitialization
virtual void SAL_CALL initialize( const ::com::sun::star::uno::Sequence< ::com::sun::star::uno::Any >& aArguments )
throw (::com::sun::star::uno::Exception, ::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
// XServiceInfo
virtual OUString SAL_CALL getImplementationName( )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
virtual sal_Bool SAL_CALL supportsService( const OUString& ServiceName )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
virtual ::com::sun::star::uno::Sequence< OUString > SAL_CALL getSupportedServiceNames( )
throw (::com::sun::star::uno::RuntimeException, std::exception) SAL_OVERRIDE;
};
OUString XmlFilterAdaptor_getImplementationName()
throw ( ::com::sun::star::uno::RuntimeException );
sal_Bool SAL_CALL XmlFilterAdaptor_supportsService( const OUString& ServiceName )
throw ( ::com::sun::star::uno::RuntimeException );
::com::sun::star::uno::Sequence< OUString > SAL_CALL XmlFilterAdaptor_getSupportedServiceNames( )
throw ( ::com::sun::star::uno::RuntimeException );
::com::sun::star::uno::Reference< ::com::sun::star::uno::XInterface >
SAL_CALL XmlFilterAdaptor_createInstance( const ::com::sun::star::uno::Reference< ::com::sun::star::lang::XMultiServiceFactory > & rSMgr)
throw ( ::com::sun::star::uno::Exception );
#endif
/* vim:set shiftwidth=4 softtabstop=4 expandtab: */
<|endoftext|> |
<commit_before>/*
* Copyright 2014 Google Inc.
*
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
#include "GrGLSLFragmentShaderBuilder.h"
#include "GrRenderTarget.h"
#include "glsl/GrGLSL.h"
#include "glsl/GrGLSLCaps.h"
#include "glsl/GrGLSLProgramBuilder.h"
#include "glsl/GrGLSLUniformHandler.h"
#include "glsl/GrGLSLVarying.h"
const char* GrGLSLFragmentShaderBuilder::kDstTextureColorName = "_dstColor";
static const char* specific_layout_qualifier_name(GrBlendEquation equation) {
SkASSERT(GrBlendEquationIsAdvanced(equation));
static const char* kLayoutQualifierNames[] = {
"blend_support_screen",
"blend_support_overlay",
"blend_support_darken",
"blend_support_lighten",
"blend_support_colordodge",
"blend_support_colorburn",
"blend_support_hardlight",
"blend_support_softlight",
"blend_support_difference",
"blend_support_exclusion",
"blend_support_multiply",
"blend_support_hsl_hue",
"blend_support_hsl_saturation",
"blend_support_hsl_color",
"blend_support_hsl_luminosity"
};
return kLayoutQualifierNames[equation - kFirstAdvancedGrBlendEquation];
GR_STATIC_ASSERT(0 == kScreen_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(1 == kOverlay_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(2 == kDarken_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(3 == kLighten_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(4 == kColorDodge_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(5 == kColorBurn_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(6 == kHardLight_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(7 == kSoftLight_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(8 == kDifference_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(9 == kExclusion_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(10 == kMultiply_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(11 == kHSLHue_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(12 == kHSLSaturation_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(13 == kHSLColor_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(14 == kHSLLuminosity_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(SK_ARRAY_COUNT(kLayoutQualifierNames) ==
kGrBlendEquationCnt - kFirstAdvancedGrBlendEquation);
}
GrGLSLFragmentShaderBuilder::FragPosKey
GrGLSLFragmentShaderBuilder::KeyForFragmentPosition(const GrRenderTarget* dst) {
if (kTopLeft_GrSurfaceOrigin == dst->origin()) {
return kTopLeftFragPosRead_FragPosKey;
} else {
return kBottomLeftFragPosRead_FragPosKey;
}
}
GrGLSLFragmentShaderBuilder::GrGLSLFragmentShaderBuilder(GrGLSLProgramBuilder* program,
uint8_t fragPosKey)
: INHERITED(program)
, fSetupFragPosition(false)
, fTopLeftFragPosRead(kTopLeftFragPosRead_FragPosKey == fragPosKey)
, fCustomColorOutputIndex(-1)
, fHasReadDstColor(false)
, fHasReadFragmentPosition(false) {
}
bool GrGLSLFragmentShaderBuilder::enableFeature(GLSLFeature feature) {
switch (feature) {
case kStandardDerivatives_GLSLFeature: {
if (!fProgramBuilder->glslCaps()->shaderDerivativeSupport()) {
return false;
}
const char* extension = fProgramBuilder->glslCaps()->shaderDerivativeExtensionString();
if (extension) {
this->addFeature(1 << kStandardDerivatives_GLSLFeature, extension);
}
return true;
}
default:
SkFAIL("Unexpected GLSLFeature requested.");
return false;
}
}
SkString GrGLSLFragmentShaderBuilder::ensureFSCoords2D(const GrGLSLTransformedCoordsArray& coords,
int index) {
if (kVec3f_GrSLType != coords[index].getType()) {
SkASSERT(kVec2f_GrSLType == coords[index].getType());
return coords[index].getName();
}
SkString coords2D("coords2D");
if (0 != index) {
coords2D.appendf("_%i", index);
}
this->codeAppendf("\tvec2 %s = %s.xy / %s.z;",
coords2D.c_str(), coords[index].c_str(), coords[index].c_str());
return coords2D;
}
const char* GrGLSLFragmentShaderBuilder::fragmentPosition() {
fHasReadFragmentPosition = true;
const GrGLSLCaps* glslCaps = fProgramBuilder->glslCaps();
// We only declare "gl_FragCoord" when we're in the case where we want to use layout qualifiers
// to reverse y. Otherwise it isn't necessary and whether the "in" qualifier appears in the
// declaration varies in earlier GLSL specs. So it is simpler to omit it.
if (fTopLeftFragPosRead) {
fSetupFragPosition = true;
return "gl_FragCoord";
} else if (const char* extension = glslCaps->fragCoordConventionsExtensionString()) {
if (!fSetupFragPosition) {
if (glslCaps->generation() < k150_GrGLSLGeneration) {
this->addFeature(1 << kFragCoordConventions_GLSLPrivateFeature,
extension);
}
fInputs.push_back().set(kVec4f_GrSLType,
GrGLSLShaderVar::kIn_TypeModifier,
"gl_FragCoord",
kDefault_GrSLPrecision,
GrGLSLShaderVar::kUpperLeft_Origin);
fSetupFragPosition = true;
}
return "gl_FragCoord";
} else {
static const char* kTempName = "tmpXYFragCoord";
static const char* kCoordName = "fragCoordYDown";
if (!fSetupFragPosition) {
const char* rtHeightName;
fProgramBuilder->addRTHeightUniform("RTHeight", &rtHeightName);
// The Adreno compiler seems to be very touchy about access to "gl_FragCoord".
// Accessing glFragCoord.zw can cause a program to fail to link. Additionally,
// depending on the surrounding code, accessing .xy with a uniform involved can
// do the same thing. Copying gl_FragCoord.xy into a temp vec2 beforehand
// (and only accessing .xy) seems to "fix" things.
this->codePrependf("\tvec4 %s = vec4(%s.x, %s - %s.y, 1.0, 1.0);\n",
kCoordName, kTempName, rtHeightName, kTempName);
this->codePrependf("vec2 %s = gl_FragCoord.xy;", kTempName);
fSetupFragPosition = true;
}
SkASSERT(fProgramBuilder->fUniformHandles.fRTHeightUni.isValid());
return kCoordName;
}
}
const char* GrGLSLFragmentShaderBuilder::dstColor() {
fHasReadDstColor = true;
const GrGLSLCaps* glslCaps = fProgramBuilder->glslCaps();
if (glslCaps->fbFetchSupport()) {
this->addFeature(1 << (GrGLSLFragmentShaderBuilder::kLastGLSLPrivateFeature + 1),
glslCaps->fbFetchExtensionString());
// Some versions of this extension string require declaring custom color output on ES 3.0+
const char* fbFetchColorName = glslCaps->fbFetchColorName();
if (glslCaps->fbFetchNeedsCustomOutput()) {
this->enableCustomOutput();
fOutputs[fCustomColorOutputIndex].setTypeModifier(GrShaderVar::kInOut_TypeModifier);
fbFetchColorName = DeclaredColorOutputName();
}
return fbFetchColorName;
} else {
return kDstTextureColorName;
}
}
void GrGLSLFragmentShaderBuilder::enableAdvancedBlendEquationIfNeeded(GrBlendEquation equation) {
SkASSERT(GrBlendEquationIsAdvanced(equation));
const GrGLSLCaps& caps = *fProgramBuilder->glslCaps();
if (!caps.mustEnableAdvBlendEqs()) {
return;
}
this->addFeature(1 << kBlendEquationAdvanced_GLSLPrivateFeature,
"GL_KHR_blend_equation_advanced");
if (caps.mustEnableSpecificAdvBlendEqs()) {
this->addLayoutQualifier(specific_layout_qualifier_name(equation), kOut_InterfaceQualifier);
} else {
this->addLayoutQualifier("blend_support_all_equations", kOut_InterfaceQualifier);
}
}
void GrGLSLFragmentShaderBuilder::enableCustomOutput() {
if (!fHasCustomColorOutput) {
fHasCustomColorOutput = true;
fCustomColorOutputIndex = fOutputs.count();
fOutputs.push_back().set(kVec4f_GrSLType,
GrGLSLShaderVar::kOut_TypeModifier,
DeclaredColorOutputName());
}
}
void GrGLSLFragmentShaderBuilder::enableSecondaryOutput() {
SkASSERT(!fHasSecondaryOutput);
fHasSecondaryOutput = true;
const GrGLSLCaps& caps = *fProgramBuilder->glslCaps();
if (const char* extension = caps.secondaryOutputExtensionString()) {
this->addFeature(1 << kBlendFuncExtended_GLSLPrivateFeature, extension);
}
// If the primary output is declared, we must declare also the secondary output
// and vice versa, since it is not allowed to use a built-in gl_FragColor and a custom
// output. The condition also co-incides with the condition in whici GLES SL 2.0
// requires the built-in gl_SecondaryFragColorEXT, where as 3.0 requires a custom output.
if (caps.mustDeclareFragmentShaderOutput()) {
fOutputs.push_back().set(kVec4f_GrSLType, GrGLSLShaderVar::kOut_TypeModifier,
DeclaredSecondaryColorOutputName());
}
}
const char* GrGLSLFragmentShaderBuilder::getPrimaryColorOutputName() const {
return fHasCustomColorOutput ? DeclaredColorOutputName() : "gl_FragColor";
}
const char* GrGLSLFragmentShaderBuilder::getSecondaryColorOutputName() const {
const GrGLSLCaps& caps = *fProgramBuilder->glslCaps();
return caps.mustDeclareFragmentShaderOutput() ? DeclaredSecondaryColorOutputName()
: "gl_SecondaryFragColorEXT";
}
void GrGLSLFragmentShaderBuilder::onFinalize() {
fProgramBuilder->varyingHandler()->getFragDecls(&this->inputs(), &this->outputs());
GrGLSLAppendDefaultFloatPrecisionDeclaration(kDefault_GrSLPrecision,
*fProgramBuilder->glslCaps(),
&this->precisionQualifier());
}
void GrGLSLFragmentBuilder::onBeforeChildProcEmitCode() {
SkASSERT(fSubstageIndices.count() >= 1);
fSubstageIndices.push_back(0);
// second-to-last value in the fSubstageIndices stack is the index of the child proc
// at that level which is currently emitting code.
fMangleString.appendf("_c%d", fSubstageIndices[fSubstageIndices.count() - 2]);
}
void GrGLSLFragmentBuilder::onAfterChildProcEmitCode() {
SkASSERT(fSubstageIndices.count() >= 2);
fSubstageIndices.pop_back();
fSubstageIndices.back()++;
int removeAt = fMangleString.findLastOf('_');
fMangleString.remove(removeAt, fMangleString.size() - removeAt);
}
<commit_msg>Switch fragment coordinate to 'highp' to fix various broken GMs.<commit_after>/*
* Copyright 2014 Google Inc.
*
* Use of this source code is governed by a BSD-style license that can be
* found in the LICENSE file.
*/
#include "GrGLSLFragmentShaderBuilder.h"
#include "GrRenderTarget.h"
#include "glsl/GrGLSL.h"
#include "glsl/GrGLSLCaps.h"
#include "glsl/GrGLSLProgramBuilder.h"
#include "glsl/GrGLSLUniformHandler.h"
#include "glsl/GrGLSLVarying.h"
const char* GrGLSLFragmentShaderBuilder::kDstTextureColorName = "_dstColor";
static const char* specific_layout_qualifier_name(GrBlendEquation equation) {
SkASSERT(GrBlendEquationIsAdvanced(equation));
static const char* kLayoutQualifierNames[] = {
"blend_support_screen",
"blend_support_overlay",
"blend_support_darken",
"blend_support_lighten",
"blend_support_colordodge",
"blend_support_colorburn",
"blend_support_hardlight",
"blend_support_softlight",
"blend_support_difference",
"blend_support_exclusion",
"blend_support_multiply",
"blend_support_hsl_hue",
"blend_support_hsl_saturation",
"blend_support_hsl_color",
"blend_support_hsl_luminosity"
};
return kLayoutQualifierNames[equation - kFirstAdvancedGrBlendEquation];
GR_STATIC_ASSERT(0 == kScreen_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(1 == kOverlay_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(2 == kDarken_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(3 == kLighten_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(4 == kColorDodge_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(5 == kColorBurn_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(6 == kHardLight_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(7 == kSoftLight_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(8 == kDifference_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(9 == kExclusion_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(10 == kMultiply_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(11 == kHSLHue_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(12 == kHSLSaturation_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(13 == kHSLColor_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(14 == kHSLLuminosity_GrBlendEquation - kFirstAdvancedGrBlendEquation);
GR_STATIC_ASSERT(SK_ARRAY_COUNT(kLayoutQualifierNames) ==
kGrBlendEquationCnt - kFirstAdvancedGrBlendEquation);
}
GrGLSLFragmentShaderBuilder::FragPosKey
GrGLSLFragmentShaderBuilder::KeyForFragmentPosition(const GrRenderTarget* dst) {
if (kTopLeft_GrSurfaceOrigin == dst->origin()) {
return kTopLeftFragPosRead_FragPosKey;
} else {
return kBottomLeftFragPosRead_FragPosKey;
}
}
GrGLSLFragmentShaderBuilder::GrGLSLFragmentShaderBuilder(GrGLSLProgramBuilder* program,
uint8_t fragPosKey)
: INHERITED(program)
, fSetupFragPosition(false)
, fTopLeftFragPosRead(kTopLeftFragPosRead_FragPosKey == fragPosKey)
, fCustomColorOutputIndex(-1)
, fHasReadDstColor(false)
, fHasReadFragmentPosition(false) {
}
bool GrGLSLFragmentShaderBuilder::enableFeature(GLSLFeature feature) {
switch (feature) {
case kStandardDerivatives_GLSLFeature: {
if (!fProgramBuilder->glslCaps()->shaderDerivativeSupport()) {
return false;
}
const char* extension = fProgramBuilder->glslCaps()->shaderDerivativeExtensionString();
if (extension) {
this->addFeature(1 << kStandardDerivatives_GLSLFeature, extension);
}
return true;
}
default:
SkFAIL("Unexpected GLSLFeature requested.");
return false;
}
}
SkString GrGLSLFragmentShaderBuilder::ensureFSCoords2D(const GrGLSLTransformedCoordsArray& coords,
int index) {
if (kVec3f_GrSLType != coords[index].getType()) {
SkASSERT(kVec2f_GrSLType == coords[index].getType());
return coords[index].getName();
}
SkString coords2D("coords2D");
if (0 != index) {
coords2D.appendf("_%i", index);
}
this->codeAppendf("\tvec2 %s = %s.xy / %s.z;",
coords2D.c_str(), coords[index].c_str(), coords[index].c_str());
return coords2D;
}
const char* GrGLSLFragmentShaderBuilder::fragmentPosition() {
fHasReadFragmentPosition = true;
const GrGLSLCaps* glslCaps = fProgramBuilder->glslCaps();
// We only declare "gl_FragCoord" when we're in the case where we want to use layout qualifiers
// to reverse y. Otherwise it isn't necessary and whether the "in" qualifier appears in the
// declaration varies in earlier GLSL specs. So it is simpler to omit it.
if (fTopLeftFragPosRead) {
fSetupFragPosition = true;
return "gl_FragCoord";
} else if (const char* extension = glslCaps->fragCoordConventionsExtensionString()) {
if (!fSetupFragPosition) {
if (glslCaps->generation() < k150_GrGLSLGeneration) {
this->addFeature(1 << kFragCoordConventions_GLSLPrivateFeature,
extension);
}
fInputs.push_back().set(kVec4f_GrSLType,
GrGLSLShaderVar::kIn_TypeModifier,
"gl_FragCoord",
kDefault_GrSLPrecision,
GrGLSLShaderVar::kUpperLeft_Origin);
fSetupFragPosition = true;
}
return "gl_FragCoord";
} else {
static const char* kTempName = "tmpXYFragCoord";
static const char* kCoordName = "fragCoordYDown";
if (!fSetupFragPosition) {
const char* rtHeightName;
fProgramBuilder->addRTHeightUniform("RTHeight", &rtHeightName);
// The Adreno compiler seems to be very touchy about access to "gl_FragCoord".
// Accessing glFragCoord.zw can cause a program to fail to link. Additionally,
// depending on the surrounding code, accessing .xy with a uniform involved can
// do the same thing. Copying gl_FragCoord.xy into a temp vec2 beforehand
// (and only accessing .xy) seems to "fix" things.
const char* precision = glslCaps->usesPrecisionModifiers() ? "highp " : "";
this->codePrependf("\t%svec4 %s = vec4(%s.x, %s - %s.y, 1.0, 1.0);\n",
precision, kCoordName, kTempName, rtHeightName, kTempName);
this->codePrependf("%svec2 %s = gl_FragCoord.xy;", precision, kTempName);
fSetupFragPosition = true;
}
SkASSERT(fProgramBuilder->fUniformHandles.fRTHeightUni.isValid());
return kCoordName;
}
}
const char* GrGLSLFragmentShaderBuilder::dstColor() {
fHasReadDstColor = true;
const GrGLSLCaps* glslCaps = fProgramBuilder->glslCaps();
if (glslCaps->fbFetchSupport()) {
this->addFeature(1 << (GrGLSLFragmentShaderBuilder::kLastGLSLPrivateFeature + 1),
glslCaps->fbFetchExtensionString());
// Some versions of this extension string require declaring custom color output on ES 3.0+
const char* fbFetchColorName = glslCaps->fbFetchColorName();
if (glslCaps->fbFetchNeedsCustomOutput()) {
this->enableCustomOutput();
fOutputs[fCustomColorOutputIndex].setTypeModifier(GrShaderVar::kInOut_TypeModifier);
fbFetchColorName = DeclaredColorOutputName();
}
return fbFetchColorName;
} else {
return kDstTextureColorName;
}
}
void GrGLSLFragmentShaderBuilder::enableAdvancedBlendEquationIfNeeded(GrBlendEquation equation) {
SkASSERT(GrBlendEquationIsAdvanced(equation));
const GrGLSLCaps& caps = *fProgramBuilder->glslCaps();
if (!caps.mustEnableAdvBlendEqs()) {
return;
}
this->addFeature(1 << kBlendEquationAdvanced_GLSLPrivateFeature,
"GL_KHR_blend_equation_advanced");
if (caps.mustEnableSpecificAdvBlendEqs()) {
this->addLayoutQualifier(specific_layout_qualifier_name(equation), kOut_InterfaceQualifier);
} else {
this->addLayoutQualifier("blend_support_all_equations", kOut_InterfaceQualifier);
}
}
void GrGLSLFragmentShaderBuilder::enableCustomOutput() {
if (!fHasCustomColorOutput) {
fHasCustomColorOutput = true;
fCustomColorOutputIndex = fOutputs.count();
fOutputs.push_back().set(kVec4f_GrSLType,
GrGLSLShaderVar::kOut_TypeModifier,
DeclaredColorOutputName());
}
}
void GrGLSLFragmentShaderBuilder::enableSecondaryOutput() {
SkASSERT(!fHasSecondaryOutput);
fHasSecondaryOutput = true;
const GrGLSLCaps& caps = *fProgramBuilder->glslCaps();
if (const char* extension = caps.secondaryOutputExtensionString()) {
this->addFeature(1 << kBlendFuncExtended_GLSLPrivateFeature, extension);
}
// If the primary output is declared, we must declare also the secondary output
// and vice versa, since it is not allowed to use a built-in gl_FragColor and a custom
// output. The condition also co-incides with the condition in whici GLES SL 2.0
// requires the built-in gl_SecondaryFragColorEXT, where as 3.0 requires a custom output.
if (caps.mustDeclareFragmentShaderOutput()) {
fOutputs.push_back().set(kVec4f_GrSLType, GrGLSLShaderVar::kOut_TypeModifier,
DeclaredSecondaryColorOutputName());
}
}
const char* GrGLSLFragmentShaderBuilder::getPrimaryColorOutputName() const {
return fHasCustomColorOutput ? DeclaredColorOutputName() : "gl_FragColor";
}
const char* GrGLSLFragmentShaderBuilder::getSecondaryColorOutputName() const {
const GrGLSLCaps& caps = *fProgramBuilder->glslCaps();
return caps.mustDeclareFragmentShaderOutput() ? DeclaredSecondaryColorOutputName()
: "gl_SecondaryFragColorEXT";
}
void GrGLSLFragmentShaderBuilder::onFinalize() {
fProgramBuilder->varyingHandler()->getFragDecls(&this->inputs(), &this->outputs());
GrGLSLAppendDefaultFloatPrecisionDeclaration(kDefault_GrSLPrecision,
*fProgramBuilder->glslCaps(),
&this->precisionQualifier());
}
void GrGLSLFragmentBuilder::onBeforeChildProcEmitCode() {
SkASSERT(fSubstageIndices.count() >= 1);
fSubstageIndices.push_back(0);
// second-to-last value in the fSubstageIndices stack is the index of the child proc
// at that level which is currently emitting code.
fMangleString.appendf("_c%d", fSubstageIndices[fSubstageIndices.count() - 2]);
}
void GrGLSLFragmentBuilder::onAfterChildProcEmitCode() {
SkASSERT(fSubstageIndices.count() >= 2);
fSubstageIndices.pop_back();
fSubstageIndices.back()++;
int removeAt = fMangleString.findLastOf('_');
fMangleString.remove(removeAt, fMangleString.size() - removeAt);
}
<|endoftext|> |
<commit_before>//$Id: Srch2Server.cpp 3456 2013-06-14 02:11:13Z jiaying $
#include <syslog.h>
#include "Srch2Server.h"
#include "util/RecordSerializerUtil.h"
namespace srch2
{
namespace httpwrapper
{
const char *HTTPServerEndpoints::index_search_url = "/srch2/search";
const char *HTTPServerEndpoints::index_info_url = "/srch2/info";
const char *HTTPServerEndpoints::cache_clear_url = "/srch2/clear";
const char *HTTPServerEndpoints::index_insert_url = "/srch2/index/insert";
const char *HTTPServerEndpoints::index_delete_url = "/srch2/index/delete";
const char *HTTPServerEndpoints::index_save_url = "/srch2/index/save";
const char *HTTPServerEndpoints::index_merge_url = "/srch2/index/merge";
const char *HTTPServerEndpoints::index_stop_url = "/srch2/stop";
/*const char *ajax_reply_start =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";*/
// CHENLI
/*const char *HTTPServerEndpoints::ajax_search_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/json\r\n"
"Content-Length:%s\n"
"\r\n";*/
const char *HTTPServerEndpoints::ajax_search_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_pass =
"HTTP/1.1 201 Created\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_fail_403 =
"HTTP/1.1 403 Forbidden\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_fail_500 =
"HTTP/1.1 500 Internal Server Error\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_save_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_merge_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
//TODO: NO way to tell if save failed on srch2 index
/*const char *ajax_save_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";*/
const char *HTTPServerEndpoints::ajax_delete_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_delete_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_delete_fail_500 =
"HTTP/1.1 500 Internal Server Error\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
bool Srch2Server::checkIndexExistence(const CoreInfo_t *indexDataConfig)
{
const string &directoryName = indexDataConfig->getIndexPath();
if(!checkDirExistence((directoryName + "/" + IndexConfig::analyzerFileName).c_str()))
return false;
if(!checkDirExistence((directoryName + "/" + IndexConfig::trieFileName).c_str()))
return false;
if(!checkDirExistence((directoryName + "/" + IndexConfig::forwardIndexFileName).c_str()))
return false;
if(!checkDirExistence((directoryName + "/" + IndexConfig::schemaFileName).c_str()))
return false;
if (indexDataConfig->getIndexType() == srch2::instantsearch::DefaultIndex){
// Check existence of the inverted index file for basic keyword search ("A1")
if(!checkDirExistence((directoryName + "/" + IndexConfig::invertedIndexFileName).c_str()))
return false;
}else{
// Check existence of the quadtree index file for geo keyword search ("M1")
if(!checkDirExistence((directoryName + "/" + IndexConfig::quadTreeFileName).c_str()))
return false;
}
return true;
}
IndexMetaData *Srch2Server::createIndexMetaData(const CoreInfo_t *indexDataConfig)
{
//Create a cache
srch2is::GlobalCache *cache = srch2is::GlobalCache::create(indexDataConfig->getCacheSizeInBytes(), 200000);
// Create an IndexMetaData
srch2is::IndexMetaData *indexMetaData =
new srch2is::IndexMetaData( cache,
indexDataConfig->getMergeEveryNSeconds(),
indexDataConfig->getMergeEveryMWrites(),
indexDataConfig->getUpdateHistogramEveryPMerges(),
indexDataConfig->getUpdateHistogramEveryQWrites(),
indexDataConfig->getIndexPath());
return indexMetaData;
}
void Srch2Server::createHighlightAttributesVector(const srch2is::Schema * schema) {
CoreInfo_t *indexConfig = const_cast<CoreInfo_t *> (this->indexDataConfig);
vector<std::pair<unsigned, string> > highlightAttributes;
const map<string, SearchableAttributeInfoContainer > * searchableAttrsFromConfig
= indexConfig->getSearchableAttributes();
map<string, SearchableAttributeInfoContainer >::const_iterator cIter;
std::map<std::string, unsigned>::const_iterator iter =
schema->getSearchableAttribute().begin();
for ( ; iter != schema->getSearchableAttribute().end(); iter++)
{
// Currently only searchable attributes are highlightable. Cross validate the schema
// attribute with configuration attributes. (There could be a mismatch when index is loaded
// from file).
cIter = searchableAttrsFromConfig->find(iter->first);
if (cIter != searchableAttrsFromConfig->end() && cIter->second.highlight)
{
highlightAttributes.push_back(make_pair(iter->second, iter->first));
}
}
indexConfig->setHighlightAttributeIdsVector(highlightAttributes);
}
void Srch2Server::createAndBootStrapIndexer()
{
// create IndexMetaData
IndexMetaData *indexMetaData = createIndexMetaData(this->indexDataConfig);
IndexCreateOrLoad indexCreateOrLoad;
if(checkIndexExistence(indexDataConfig))
indexCreateOrLoad = srch2http::INDEXLOAD;
else
indexCreateOrLoad = srch2http::INDEXCREATE;
Schema * storedAttrSchema = Schema::create();
switch (indexCreateOrLoad)
{
case srch2http::INDEXCREATE:
{
AnalyzerHelper::initializeAnalyzerResource(this->indexDataConfig);
// Create a schema to the data source definition in the Srch2ServerConf
srch2is::Schema *schema = JSONRecordParser::createAndPopulateSchema(indexDataConfig);
Analyzer *analyzer = AnalyzerFactory::createAnalyzer(this->indexDataConfig);
indexer = Indexer::create(indexMetaData, analyzer, schema);
delete analyzer;
delete schema;
switch(indexDataConfig->getDataSourceType())
{
case srch2http::DATA_SOURCE_JSON_FILE:
{
// Create from JSON and save to index-dir
Logger::console("Creating indexes from JSON file...");
RecordSerializerUtil::populateStoredSchema(storedAttrSchema, indexer->getSchema());
unsigned indexedCounter = DaemonDataSource::createNewIndexFromFile(indexer,
storedAttrSchema, indexDataConfig);
/*
* commit the indexes once bulk load is done and then save it to the disk only
* if number of indexed record is > 0.
*/
indexer->commit();
if (indexedCounter > 0) {
indexer->save();
Logger::console("Indexes saved.");
}
break;
}
case srch2http::DATA_SOURCE_MONGO_DB:
{
Logger::console("Creating indexes from a MongoDb instance...");
unsigned indexedCounter = MongoDataSource::createNewIndexes(indexer, indexDataConfig);
indexer->commit();
if (indexedCounter > 0) {
indexer->save();
Logger::console("Indexes saved.");
}
break;
}
default:
{
indexer->commit();
Logger::console("Creating new empty index");
}
};
AnalyzerHelper::saveAnalyzerResource(this->indexDataConfig);
break;
}
case srch2http::INDEXLOAD:
{
// Load from index-dir directly, skip creating an index initially.
indexer = Indexer::load(indexMetaData);
// Load Analayzer data from disk
AnalyzerHelper::loadAnalyzerResource(this->indexDataConfig);
indexer->getSchema()->setSupportSwapInEditDistance(indexDataConfig->getSupportSwapInEditDistance());
bool isAttributeBasedSearch = false;
if (isEnabledAttributeBasedSearch(indexer->getSchema()->getPositionIndexType())) {
isAttributeBasedSearch =true;
}
if(isAttributeBasedSearch != indexDataConfig->getSupportAttributeBasedSearch())
{
Logger::warn("support-attribute-based-search has changed in the config file"
" remove all index files and run it again!");
}
RecordSerializerUtil::populateStoredSchema(storedAttrSchema, indexer->getSchema());
break;
}
}
createHighlightAttributesVector(storedAttrSchema);
delete storedAttrSchema;
// start merger thread
indexer->createAndStartMergeThreadLoop();
}
void Srch2Server::setCoreName(const string &name)
{
coreName = name;
}
const string &Srch2Server::getCoreName()
{
return coreName;
}
}
}
<commit_msg>fixed indentation<commit_after>//$Id: Srch2Server.cpp 3456 2013-06-14 02:11:13Z jiaying $
#include <syslog.h>
#include "Srch2Server.h"
#include "util/RecordSerializerUtil.h"
namespace srch2
{
namespace httpwrapper
{
const char *HTTPServerEndpoints::index_search_url = "/srch2/search";
const char *HTTPServerEndpoints::index_info_url = "/srch2/info";
const char *HTTPServerEndpoints::cache_clear_url = "/srch2/clear";
const char *HTTPServerEndpoints::index_insert_url = "/srch2/index/insert";
const char *HTTPServerEndpoints::index_delete_url = "/srch2/index/delete";
const char *HTTPServerEndpoints::index_save_url = "/srch2/index/save";
const char *HTTPServerEndpoints::index_merge_url = "/srch2/index/merge";
const char *HTTPServerEndpoints::index_stop_url = "/srch2/stop";
/*const char *ajax_reply_start =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";*/
// CHENLI
/*const char *HTTPServerEndpoints::ajax_search_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/json\r\n"
"Content-Length:%s\n"
"\r\n";*/
const char *HTTPServerEndpoints::ajax_search_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_pass =
"HTTP/1.1 201 Created\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_fail_403 =
"HTTP/1.1 403 Forbidden\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_insert_fail_500 =
"HTTP/1.1 500 Internal Server Error\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_save_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_merge_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
//TODO: NO way to tell if save failed on srch2 index
/*const char *ajax_save_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";*/
const char *HTTPServerEndpoints::ajax_delete_pass =
"HTTP/1.1 200 OK\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_delete_fail =
"HTTP/1.1 400 Bad Request\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
const char *HTTPServerEndpoints::ajax_delete_fail_500 =
"HTTP/1.1 500 Internal Server Error\r\n"
"Cache: no-cache\r\n"
"Content-Type: application/x-javascript\r\n"
"\r\n";
bool Srch2Server::checkIndexExistence(const CoreInfo_t *indexDataConfig)
{
const string &directoryName = indexDataConfig->getIndexPath();
if(!checkDirExistence((directoryName + "/" + IndexConfig::analyzerFileName).c_str()))
return false;
if(!checkDirExistence((directoryName + "/" + IndexConfig::trieFileName).c_str()))
return false;
if(!checkDirExistence((directoryName + "/" + IndexConfig::forwardIndexFileName).c_str()))
return false;
if(!checkDirExistence((directoryName + "/" + IndexConfig::schemaFileName).c_str()))
return false;
if (indexDataConfig->getIndexType() == srch2::instantsearch::DefaultIndex){
// Check existence of the inverted index file for basic keyword search ("A1")
if(!checkDirExistence((directoryName + "/" + IndexConfig::invertedIndexFileName).c_str()))
return false;
}else{
// Check existence of the quadtree index file for geo keyword search ("M1")
if(!checkDirExistence((directoryName + "/" + IndexConfig::quadTreeFileName).c_str()))
return false;
}
return true;
}
IndexMetaData *Srch2Server::createIndexMetaData(const CoreInfo_t *indexDataConfig)
{
//Create a cache
srch2is::GlobalCache *cache = srch2is::GlobalCache::create(indexDataConfig->getCacheSizeInBytes(), 200000);
// Create an IndexMetaData
srch2is::IndexMetaData *indexMetaData =
new srch2is::IndexMetaData( cache,
indexDataConfig->getMergeEveryNSeconds(),
indexDataConfig->getMergeEveryMWrites(),
indexDataConfig->getUpdateHistogramEveryPMerges(),
indexDataConfig->getUpdateHistogramEveryQWrites(),
indexDataConfig->getIndexPath());
return indexMetaData;
}
void Srch2Server::createHighlightAttributesVector(const srch2is::Schema * schema) {
CoreInfo_t *indexConfig = const_cast<CoreInfo_t *> (this->indexDataConfig);
vector<std::pair<unsigned, string> > highlightAttributes;
const map<string, SearchableAttributeInfoContainer > * searchableAttrsFromConfig
= indexConfig->getSearchableAttributes();
map<string, SearchableAttributeInfoContainer >::const_iterator cIter;
std::map<std::string, unsigned>::const_iterator iter =
schema->getSearchableAttribute().begin();
for ( ; iter != schema->getSearchableAttribute().end(); iter++)
{
// Currently only searchable attributes are highlightable. Cross validate the schema
// attribute with configuration attributes. (There could be a mismatch when index is loaded
// from file).
cIter = searchableAttrsFromConfig->find(iter->first);
if (cIter != searchableAttrsFromConfig->end() && cIter->second.highlight)
{
highlightAttributes.push_back(make_pair(iter->second, iter->first));
}
}
indexConfig->setHighlightAttributeIdsVector(highlightAttributes);
}
void Srch2Server::createAndBootStrapIndexer()
{
// create IndexMetaData
IndexMetaData *indexMetaData = createIndexMetaData(this->indexDataConfig);
IndexCreateOrLoad indexCreateOrLoad;
if(checkIndexExistence(indexDataConfig))
indexCreateOrLoad = srch2http::INDEXLOAD;
else
indexCreateOrLoad = srch2http::INDEXCREATE;
Schema * storedAttrSchema = Schema::create();
switch (indexCreateOrLoad)
{
case srch2http::INDEXCREATE:
{
AnalyzerHelper::initializeAnalyzerResource(this->indexDataConfig);
// Create a schema to the data source definition in the Srch2ServerConf
srch2is::Schema *schema = JSONRecordParser::createAndPopulateSchema(indexDataConfig);
Analyzer *analyzer = AnalyzerFactory::createAnalyzer(this->indexDataConfig);
indexer = Indexer::create(indexMetaData, analyzer, schema);
delete analyzer;
delete schema;
switch(indexDataConfig->getDataSourceType())
{
case srch2http::DATA_SOURCE_JSON_FILE:
{
// Create from JSON and save to index-dir
Logger::console("Creating indexes from JSON file...");
RecordSerializerUtil::populateStoredSchema(storedAttrSchema, indexer->getSchema());
unsigned indexedCounter = DaemonDataSource::createNewIndexFromFile(indexer,
storedAttrSchema, indexDataConfig);
/*
* commit the indexes once bulk load is done and then save it to the disk only
* if number of indexed record is > 0.
*/
indexer->commit();
if (indexedCounter > 0) {
indexer->save();
Logger::console("Indexes saved.");
}
break;
}
case srch2http::DATA_SOURCE_MONGO_DB:
{
Logger::console("Creating indexes from a MongoDb instance...");
unsigned indexedCounter = MongoDataSource::createNewIndexes(indexer, indexDataConfig);
indexer->commit();
if (indexedCounter > 0) {
indexer->save();
Logger::console("Indexes saved.");
}
break;
}
default:
{
indexer->commit();
Logger::console("Creating new empty index");
}
};
AnalyzerHelper::saveAnalyzerResource(this->indexDataConfig);
break;
}
case srch2http::INDEXLOAD:
{
// Load from index-dir directly, skip creating an index initially.
indexer = Indexer::load(indexMetaData);
// Load Analayzer data from disk
AnalyzerHelper::loadAnalyzerResource(this->indexDataConfig);
indexer->getSchema()->setSupportSwapInEditDistance(indexDataConfig->getSupportSwapInEditDistance());
bool isAttributeBasedSearch = false;
if (isEnabledAttributeBasedSearch(indexer->getSchema()->getPositionIndexType())) {
isAttributeBasedSearch =true;
}
if(isAttributeBasedSearch != indexDataConfig->getSupportAttributeBasedSearch())
{
Logger::warn("support-attribute-based-search has changed in the config file"
" remove all index files and run it again!");
}
RecordSerializerUtil::populateStoredSchema(storedAttrSchema, indexer->getSchema());
break;
}
}
createHighlightAttributesVector(storedAttrSchema);
delete storedAttrSchema;
// start merger thread
indexer->createAndStartMergeThreadLoop();
}
void Srch2Server::setCoreName(const string &name)
{
coreName = name;
}
const string &Srch2Server::getCoreName()
{
return coreName;
}
}
}
<|endoftext|> |
<commit_before>/**
* Copyright (C) Mellanox Technologies Ltd. 2001-2014. ALL RIGHTS RESERVED.
* Copyright (C) UT-Battelle, LLC. 2014. ALL RIGHTS RESERVED.
* See file LICENSE for terms.
*/
extern "C" {
#include <uct/api/uct.h>
#include <ucs/time/time.h>
}
#include <common/test.h>
#include "uct_test.h"
class test_uct_pending : public uct_test {
public:
void initialize() {
uct_test::init();
m_e1 = uct_test::create_entity(0);
m_e2 = uct_test::create_entity(0);
m_e1->connect(0, *m_e2, 0);
m_e2->connect(0, *m_e1, 0);
m_entities.push_back(m_e1);
m_entities.push_back(m_e2);
}
typedef struct pending_send_request {
uct_ep_h ep;
uint64_t data;
int countdown; /* Actually send after X calls */
uct_pending_req_t uct;
} pending_send_request_t;
static ucs_status_t am_handler(void *arg, void *data, size_t length,
void *desc) {
unsigned *counter = (unsigned *) arg;
uint64_t test_hdr = *(uint64_t *) data;
uint64_t actual_data = *(unsigned*)((char*)data + sizeof(test_hdr));
if ((test_hdr == 0xabcd) && (actual_data == (0xdeadbeef + *counter))) {
(*counter)++;
} else {
UCS_TEST_ABORT("Error in comparison in pending_am_handler. Counter: " << counter);
}
return UCS_OK;
}
static ucs_status_t pending_send_op(uct_pending_req_t *self) {
pending_send_request_t *req = ucs_container_of(self, pending_send_request_t, uct);
ucs_status_t status;
if (req->countdown > 0) {
--req->countdown;
return UCS_INPROGRESS;
}
status = uct_ep_am_short(req->ep, 0, test_pending_hdr, &req->data,
sizeof(req->data));
if (status == UCS_OK) {
delete req;
}
return status;
}
pending_send_request_t* pending_alloc(uint64_t send_data) {
pending_send_request_t *req = new pending_send_request_t();
req->ep = m_e1->ep(0);
req->data = send_data;
req->countdown = 5;
req->uct.func = pending_send_op;
return req;
}
protected:
static const uint64_t test_pending_hdr = 0xabcd;
entity *m_e1, *m_e2;
};
UCS_TEST_P(test_uct_pending, pending_op)
{
uint64_t send_data = 0xdeadbeef;
ucs_status_t status;
unsigned i, iters, counter = 0;
uct_iface_attr_t attr;
initialize();
check_caps(UCT_IFACE_FLAG_AM_SHORT | UCT_IFACE_FLAG_PENDING);
iters = 1000000/ucs::test_time_multiplier();
/* set a callback for the uct to invoke for receiving the data */
uct_iface_query(m_e2->iface(), &attr);
if (attr.cap.flags & UCT_IFACE_FLAG_AM_CB_SYNC) {
uct_iface_set_am_handler(m_e2->iface(), 0, am_handler , &counter, UCT_AM_CB_FLAG_SYNC);
} else {
uct_iface_set_am_handler(m_e2->iface(), 0, am_handler , &counter, UCT_AM_CB_FLAG_ASYNC);
}
/* send the data until the resources run out */
i = 0;
while (i < iters) {
status = uct_ep_am_short(m_e1->ep(0), 0, test_pending_hdr, &send_data,
sizeof(send_data));
if (status != UCS_OK) {
if (status == UCS_ERR_NO_RESOURCE) {
pending_send_request_t *req = pending_alloc(send_data);
status = uct_ep_pending_add(m_e1->ep(0), &req->uct);
if (status != UCS_OK) {
/* the request wasn't added to the pending data structure
* since resources became available. retry sending this message */
free(req);
} else {
/* the request was added to the pending data structure */
send_data += 1;
i++;
}
/* coverity[leaked_storage] */
} else {
UCS_TEST_ABORT("Error: " << ucs_status_string(status));
}
} else {
send_data += 1;
i++;
}
}
/* coverity[loop_condition] */
while (counter != iters) {
progress();
}
ASSERT_EQ(counter, iters);
}
UCS_TEST_P(test_uct_pending, send_ooo_with_pending)
{
uint64_t send_data = 0xdeadbeef;
ucs_status_t status_send, status_pend = UCS_ERR_LAST;
ucs_time_t loop_end_limit;
unsigned i, counter = 0;
uct_iface_attr_t attr;
initialize();
check_caps(UCT_IFACE_FLAG_AM_SHORT | UCT_IFACE_FLAG_PENDING);
/* set a callback for the uct to invoke when receiving the data */
uct_iface_query(m_e2->iface(), &attr);
if (attr.cap.flags & UCT_IFACE_FLAG_AM_CB_SYNC) {
uct_iface_set_am_handler(m_e2->iface(), 0, am_handler , &counter, UCT_AM_CB_FLAG_SYNC);
} else {
uct_iface_set_am_handler(m_e2->iface(), 0, am_handler , &counter, UCT_AM_CB_FLAG_ASYNC);
}
loop_end_limit = ucs_get_time() + ucs_time_from_sec(2);
/* send while resources are available. try to add a request to pending */
do {
status_send = uct_ep_am_short(m_e1->ep(0), 0, test_pending_hdr, &send_data,
sizeof(send_data));
if (status_send == UCS_ERR_NO_RESOURCE) {
pending_send_request_t *req = pending_alloc(send_data);
status_pend = uct_ep_pending_add(m_e1->ep(0), &req->uct);
if (status_pend == UCS_ERR_BUSY) {
free(req);
} else {
/* coverity[leaked_storage] */
break;
}
} else {
send_data += 1;
}
} while (ucs_get_time() < loop_end_limit);
if ((status_send == UCS_OK) || (status_pend == UCS_ERR_BUSY)) {
/* got here due to reaching the time limit in the above loop.
* couldn't add a request to pending. all sends were successful. */
UCS_TEST_MESSAGE << "Can't create out-of-order in the given time.";
return;
}
/* there is one pending request */
EXPECT_EQ(UCS_OK, status_pend);
/* progress the receiver a bit to release resources */
for (i = 0; i < 1000; i++) {
m_e2->progress();
}
/* send a new message. the transport should make sure that this new message
* isn't sent before the one in pending, thus preventing out-of-order in sending. */
send_data += 1;
do {
status_send = uct_ep_am_short(m_e1->ep(0), 0, test_pending_hdr,
&send_data, sizeof(send_data));
short_progress_loop();
} while (status_send == UCS_ERR_NO_RESOURCE);
/* the receive side checks that the messages were received in order.
* check the last message here. (counter was raised by one for next iteration) */
EXPECT_EQ(send_data, 0xdeadbeef + counter - 1);
}
UCT_INSTANTIATE_TEST_CASE(test_uct_pending);
<commit_msg>Refactor new pending code to make it's own function<commit_after>/**
* Copyright (C) Mellanox Technologies Ltd. 2001-2014. ALL RIGHTS RESERVED.
* Copyright (C) UT-Battelle, LLC. 2014. ALL RIGHTS RESERVED.
* See file LICENSE for terms.
*/
extern "C" {
#include <uct/api/uct.h>
#include <ucs/time/time.h>
}
#include <common/test.h>
#include "uct_test.h"
class test_uct_pending : public uct_test {
public:
void initialize() {
uct_test::init();
m_e1 = uct_test::create_entity(0);
m_e2 = uct_test::create_entity(0);
m_e1->connect(0, *m_e2, 0);
m_e2->connect(0, *m_e1, 0);
m_entities.push_back(m_e1);
m_entities.push_back(m_e2);
}
typedef struct pending_send_request {
uct_ep_h ep;
uint64_t data;
int countdown; /* Actually send after X calls */
uct_pending_req_t uct;
} pending_send_request_t;
static ucs_status_t am_handler(void *arg, void *data, size_t length,
void *desc) {
unsigned *counter = (unsigned *) arg;
uint64_t test_hdr = *(uint64_t *) data;
uint64_t actual_data = *(unsigned*)((char*)data + sizeof(test_hdr));
if ((test_hdr == 0xabcd) && (actual_data == (0xdeadbeef + *counter))) {
(*counter)++;
} else {
UCS_TEST_ABORT("Error in comparison in pending_am_handler. Counter: " << counter);
}
return UCS_OK;
}
static ucs_status_t pending_send_op(uct_pending_req_t *self) {
pending_send_request_t *req = ucs_container_of(self, pending_send_request_t, uct);
ucs_status_t status;
if (req->countdown > 0) {
--req->countdown;
return UCS_INPROGRESS;
}
status = uct_ep_am_short(req->ep, 0, test_pending_hdr, &req->data,
sizeof(req->data));
if (status == UCS_OK) {
delete req;
}
return status;
}
pending_send_request_t* pending_alloc(uint64_t send_data) {
pending_send_request_t *req = new pending_send_request_t();
req->ep = m_e1->ep(0);
req->data = send_data;
req->countdown = 5;
req->uct.func = pending_send_op;
return req;
}
protected:
static const uint64_t test_pending_hdr = 0xabcd;
entity *m_e1, *m_e2;
};
void install_handler_sync_or_async(uct_iface_t *iface, uint8_t id, uct_am_callback_t cb, void *arg)
{
ucs_status_t status;
uct_iface_attr_t attr;
status = uct_iface_query(iface, &attr);
ASSERT_UCS_OK(status);
if (attr.cap.flags & UCT_IFACE_FLAG_AM_CB_SYNC) {
uct_iface_set_am_handler(iface, id, cb, arg, UCT_AM_CB_FLAG_SYNC);
} else {
uct_iface_set_am_handler(iface, id, cb, arg, UCT_AM_CB_FLAG_ASYNC);
}
}
UCS_TEST_P(test_uct_pending, pending_op)
{
uint64_t send_data = 0xdeadbeef;
ucs_status_t status;
unsigned i, iters, counter = 0;
initialize();
check_caps(UCT_IFACE_FLAG_AM_SHORT | UCT_IFACE_FLAG_PENDING);
iters = 1000000/ucs::test_time_multiplier();
/* set a callback for the uct to invoke for receiving the data */
install_handler_sync_or_async(m_e2->iface(), 0, am_handler, &counter);
/* send the data until the resources run out */
i = 0;
while (i < iters) {
status = uct_ep_am_short(m_e1->ep(0), 0, test_pending_hdr, &send_data,
sizeof(send_data));
if (status != UCS_OK) {
if (status == UCS_ERR_NO_RESOURCE) {
pending_send_request_t *req = pending_alloc(send_data);
status = uct_ep_pending_add(m_e1->ep(0), &req->uct);
if (status != UCS_OK) {
/* the request wasn't added to the pending data structure
* since resources became available. retry sending this message */
free(req);
} else {
/* the request was added to the pending data structure */
send_data += 1;
i++;
}
/* coverity[leaked_storage] */
} else {
UCS_TEST_ABORT("Error: " << ucs_status_string(status));
}
} else {
send_data += 1;
i++;
}
}
/* coverity[loop_condition] */
while (counter != iters) {
progress();
}
ASSERT_EQ(counter, iters);
}
UCS_TEST_P(test_uct_pending, send_ooo_with_pending)
{
uint64_t send_data = 0xdeadbeef;
ucs_status_t status_send, status_pend = UCS_ERR_LAST;
ucs_time_t loop_end_limit;
unsigned i, counter = 0;
initialize();
check_caps(UCT_IFACE_FLAG_AM_SHORT | UCT_IFACE_FLAG_PENDING);
/* set a callback for the uct to invoke when receiving the data */
install_handler_sync_or_async(m_e2->iface(), 0, am_handler, &counter);
loop_end_limit = ucs_get_time() + ucs_time_from_sec(2);
/* send while resources are available. try to add a request to pending */
do {
status_send = uct_ep_am_short(m_e1->ep(0), 0, test_pending_hdr, &send_data,
sizeof(send_data));
if (status_send == UCS_ERR_NO_RESOURCE) {
pending_send_request_t *req = pending_alloc(send_data);
status_pend = uct_ep_pending_add(m_e1->ep(0), &req->uct);
if (status_pend == UCS_ERR_BUSY) {
free(req);
} else {
/* coverity[leaked_storage] */
break;
}
} else {
send_data += 1;
}
} while (ucs_get_time() < loop_end_limit);
if ((status_send == UCS_OK) || (status_pend == UCS_ERR_BUSY)) {
/* got here due to reaching the time limit in the above loop.
* couldn't add a request to pending. all sends were successful. */
UCS_TEST_MESSAGE << "Can't create out-of-order in the given time.";
return;
}
/* there is one pending request */
EXPECT_EQ(UCS_OK, status_pend);
/* progress the receiver a bit to release resources */
for (i = 0; i < 1000; i++) {
m_e2->progress();
}
/* send a new message. the transport should make sure that this new message
* isn't sent before the one in pending, thus preventing out-of-order in sending. */
send_data += 1;
do {
status_send = uct_ep_am_short(m_e1->ep(0), 0, test_pending_hdr,
&send_data, sizeof(send_data));
short_progress_loop();
} while (status_send == UCS_ERR_NO_RESOURCE);
/* the receive side checks that the messages were received in order.
* check the last message here. (counter was raised by one for next iteration) */
EXPECT_EQ(send_data, 0xdeadbeef + counter - 1);
}
UCT_INSTANTIATE_TEST_CASE(test_uct_pending);
<|endoftext|> |
<commit_before>#include "shared-application.h"
#include <QtGlobal>
#ifdef Q_OS_WIN32
#ifndef _WIN32_WINNT
#define _WIN32_WINNT 0x0501
#endif
#ifndef __MSVCRT__
#define __MSVCRT__
#endif
#include <process.h>
#else
#include <pthread.h>
#endif
#if defined(__FreeBSD__) || defined(__NetBSD__) || defined(__OpenBSD__)
#include <event2/event.h>
#include <event2/event_compat.h>
#include <event2/event_struct.h>
#else
#include <event.h>
#endif
extern "C" {
#include <searpc-client.h>
#include <ccnet.h>
#include <searpc.h>
#include <seafile/seafile.h>
#include <seafile/seafile-object.h>
}
#include "utils/utils.h"
namespace {
const char *kAppletCommandsMQ = "applet.commands";
const int kWaitResponseSeconds = 6;
bool isActivate = false;
struct UserData {
struct event_base *ev_base;
_CcnetClient *ccnet_client;
};
void readCallback(int sock, short what, void* data)
{
UserData *user_data = static_cast<UserData*>(data);
if (ccnet_client_read_input(user_data->ccnet_client) <= 0) {
// fatal error
event_base_loopbreak(user_data->ev_base);
}
}
void messageCallback(CcnetMessage *message, void *data)
{
isActivate = g_strcmp0(message->body, "ack_activate") == 0;
if (isActivate) {
// time to leave
struct event_base *ev_base = static_cast<struct event_base*>(data);
event_base_loopbreak(ev_base);
}
}
#ifndef Q_OS_WIN32
void *askActivateSynchronically(void * /*arg*/) {
#else
unsigned __stdcall askActivateSynchronically(void * /*arg*/) {
#endif
_CcnetClient* async_client = ccnet_client_new();
_CcnetClient *sync_client = ccnet_client_new();
const QString ccnet_dir = defaultCcnetDir();
if (ccnet_client_load_confdir(async_client, toCStr(ccnet_dir)) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
if (ccnet_client_connect_daemon(async_client, CCNET_CLIENT_ASYNC) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
if (ccnet_client_load_confdir(sync_client, toCStr(ccnet_dir)) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
if (ccnet_client_connect_daemon(sync_client, CCNET_CLIENT_SYNC) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
//
// send message synchronously
//
CcnetMessage *syn_message;
syn_message = ccnet_message_new(sync_client->base.id,
sync_client->base.id,
kAppletCommandsMQ, "syn_activate", 0);
// blocking io, but cancellable from pthread_cancel
if (ccnet_client_send_message(sync_client, syn_message) < 0) {
ccnet_message_free(syn_message);
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
ccnet_message_free(syn_message);
//
// receive message asynchronously
//
struct event_base* ev_base = event_base_new();
struct timeval timeout;
timeout.tv_sec = kWaitResponseSeconds - 1;
timeout.tv_usec = 0;
// set timeout
event_base_loopexit(ev_base, &timeout);
UserData user_data;
user_data.ev_base = ev_base;
user_data.ccnet_client = async_client;
struct event *read_event = event_new(ev_base, async_client->connfd,
EV_READ | EV_PERSIST, readCallback, &user_data);
event_add(read_event, NULL);
// set message read callback
_CcnetMqclientProc *mqclient_proc = (CcnetMqclientProc *)
ccnet_proc_factory_create_master_processor
(async_client->proc_factory, "mq-client");
ccnet_mqclient_proc_set_message_got_cb(mqclient_proc,
messageCallback,
ev_base);
const char *topics[] = {
kAppletCommandsMQ,
};
if (ccnet_processor_start((CcnetProcessor *)mqclient_proc,
G_N_ELEMENTS(topics), (char **)topics) < 0) {
event_base_free(ev_base);
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
event_base_dispatch(ev_base);
event_base_free(ev_base);
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
} // anonymous namespace
bool SharedApplication::activate() {
#ifndef Q_OS_WIN32 // saddly, this don't work for windows
pthread_t thread;
// do it in a background thread
if (pthread_create(&thread, NULL, askActivateSynchronically, NULL) != 0) {
return false;
}
// keep wait for timeout or thread quiting
int waiting_count = kWaitResponseSeconds * 10;
// pthread_kill: currently only a value of 0 is supported on mingw
while (pthread_kill(thread, 0) == 0 && --waiting_count > 0) {
msleep(100);
}
if (waiting_count == 0) {
// saddly, pthread_cancel don't work properly on mingw
pthread_cancel(thread);
}
#else
// _beginthreadex as the document says
// https://msdn.microsoft.com/en-us/library/windows/desktop/ms682453%28v=vs.85%29.aspx
HANDLE thread = (HANDLE)_beginthreadex(NULL, 0, askActivateSynchronically, NULL, 0, NULL);
if (!thread)
return false;
// keep wait for timeout or thread quiting
if (WaitForSingleObject(thread, kWaitResponseSeconds) == WAIT_TIMEOUT) {
TerminateThread(thread, 128);
}
CloseHandle(thread);
#endif
return isActivate;
}
<commit_msg>fix a typo in previous commit<commit_after>#include "shared-application.h"
#include <QtGlobal>
#ifdef Q_OS_WIN32
#ifndef _WIN32_WINNT
#define _WIN32_WINNT 0x0501
#endif
#ifndef __MSVCRT__
#define __MSVCRT__
#endif
#include <process.h>
#else
#include <pthread.h>
#endif
#if defined(__FreeBSD__) || defined(__NetBSD__) || defined(__OpenBSD__)
#include <event2/event.h>
#include <event2/event_compat.h>
#include <event2/event_struct.h>
#else
#include <event.h>
#endif
extern "C" {
#include <searpc-client.h>
#include <ccnet.h>
#include <searpc.h>
#include <seafile/seafile.h>
#include <seafile/seafile-object.h>
}
#include "utils/utils.h"
namespace {
const char *kAppletCommandsMQ = "applet.commands";
const int kWaitResponseSeconds = 6;
bool isActivate = false;
struct UserData {
struct event_base *ev_base;
_CcnetClient *ccnet_client;
};
void readCallback(int sock, short what, void* data)
{
UserData *user_data = static_cast<UserData*>(data);
if (ccnet_client_read_input(user_data->ccnet_client) <= 0) {
// fatal error
event_base_loopbreak(user_data->ev_base);
}
}
void messageCallback(CcnetMessage *message, void *data)
{
isActivate = g_strcmp0(message->body, "ack_activate") == 0;
if (isActivate) {
// time to leave
struct event_base *ev_base = static_cast<struct event_base*>(data);
event_base_loopbreak(ev_base);
}
}
#ifndef Q_OS_WIN32
void *askActivateSynchronically(void * /*arg*/) {
#else
unsigned __stdcall askActivateSynchronically(void * /*arg*/) {
#endif
_CcnetClient* async_client = ccnet_client_new();
_CcnetClient *sync_client = ccnet_client_new();
const QString ccnet_dir = defaultCcnetDir();
if (ccnet_client_load_confdir(async_client, toCStr(ccnet_dir)) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
if (ccnet_client_connect_daemon(async_client, CCNET_CLIENT_ASYNC) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
if (ccnet_client_load_confdir(sync_client, toCStr(ccnet_dir)) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
if (ccnet_client_connect_daemon(sync_client, CCNET_CLIENT_SYNC) < 0) {
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
//
// send message synchronously
//
CcnetMessage *syn_message;
syn_message = ccnet_message_new(sync_client->base.id,
sync_client->base.id,
kAppletCommandsMQ, "syn_activate", 0);
// blocking io, but cancellable from pthread_cancel
if (ccnet_client_send_message(sync_client, syn_message) < 0) {
ccnet_message_free(syn_message);
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
ccnet_message_free(syn_message);
//
// receive message asynchronously
//
struct event_base* ev_base = event_base_new();
struct timeval timeout;
timeout.tv_sec = kWaitResponseSeconds - 1;
timeout.tv_usec = 0;
// set timeout
event_base_loopexit(ev_base, &timeout);
UserData user_data;
user_data.ev_base = ev_base;
user_data.ccnet_client = async_client;
struct event *read_event = event_new(ev_base, async_client->connfd,
EV_READ | EV_PERSIST, readCallback, &user_data);
event_add(read_event, NULL);
// set message read callback
_CcnetMqclientProc *mqclient_proc = (CcnetMqclientProc *)
ccnet_proc_factory_create_master_processor
(async_client->proc_factory, "mq-client");
ccnet_mqclient_proc_set_message_got_cb(mqclient_proc,
messageCallback,
ev_base);
const char *topics[] = {
kAppletCommandsMQ,
};
if (ccnet_processor_start((CcnetProcessor *)mqclient_proc,
G_N_ELEMENTS(topics), (char **)topics) < 0) {
event_base_free(ev_base);
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
event_base_dispatch(ev_base);
event_base_free(ev_base);
g_object_unref(sync_client);
g_object_unref(async_client);
return 0;
}
} // anonymous namespace
bool SharedApplication::activate() {
#ifndef Q_OS_WIN32 // saddly, this don't work for windows
pthread_t thread;
// do it in a background thread
if (pthread_create(&thread, NULL, askActivateSynchronically, NULL) != 0) {
return false;
}
// keep wait for timeout or thread quiting
int waiting_count = kWaitResponseSeconds * 10;
// pthread_kill: currently only a value of 0 is supported on mingw
while (pthread_kill(thread, 0) == 0 && --waiting_count > 0) {
msleep(100);
}
if (waiting_count == 0) {
// saddly, pthread_cancel don't work properly on mingw
pthread_cancel(thread);
}
#else
// _beginthreadex as the document says
// https://msdn.microsoft.com/en-us/library/windows/desktop/ms682453%28v=vs.85%29.aspx
HANDLE thread = (HANDLE)_beginthreadex(NULL, 0, askActivateSynchronically, NULL, 0, NULL);
if (!thread)
return false;
// keep wait for timeout or thread quiting
if (WaitForSingleObject(thread, kWaitResponseSeconds * 1000) == WAIT_TIMEOUT) {
TerminateThread(thread, 128);
}
CloseHandle(thread);
#endif
return isActivate;
}
<|endoftext|> |
<commit_before>#include "../stactive_record.h"
using namespace stactiverecord;
Sar_Dbi * Sar_Dbi::dbi = Sar_Dbi::makeStorage("sqlite://./sqlitedb.db");
void assert(bool v, string msg) {
if(v) return;
throw Sar_AssertionFailedException("Failed when testing " + msg);
}
int main() {
debug("Testing sqlite...");
Sar_Dbi *db = Sar_Dbi::dbi;
string classname = "testclass";
string related_classname = "testclass_related";
// recreate tables;
db->initialize_tables(classname);
// test id creation
assert(db->next_id(classname) == 0, "next_id incrementing");
assert(db->next_id(classname) == 1, "next_id incrementing");
assert(db->next_id(classname) == 2, "next_id incrementing");
assert(db->current_id(classname) == 2, "getting current id");
int id = 2;
SarMap<string> svalues;
SarMap<int> ivalues;
SarMap<string> sresults;
SarMap<int> iresults;
SarVector<int> ovalues;
SarVector<int> oresults;
SarMap< SarVector<int> > all_relationships;
// test inserts
svalues["foo"] = "bar";
svalues["baz"] = "bang";
ivalues["bar"] = 55;
ivalues["zoop"] = 1234;
db->set(id, classname, svalues, true);
db->set(id, classname, ivalues, true);
db->get(id, classname, sresults);
db->get(id, classname, iresults);
assert(sresults == svalues, "storing/retrieving string values");
assert(iresults == ivalues, "storing/retrieving int values");
// now test updates
svalues["foo"] = "oof";
svalues["baz"] = "foo";
ivalues["bar"] = 998;
ivalues["zoop"] = 5364;
db->set(id, classname, svalues, false);
db->set(id, classname, ivalues, false);
sresults.clear();
iresults.clear();
db->get(id, classname, sresults);
db->get(id, classname, iresults);
assert(sresults == svalues, "updating/retrieving string values");
assert(iresults == ivalues, "updating/retrieving int values");
// now test record relations
ovalues << 4;
ovalues << 5;
ovalues << 6;
db->set(id, classname, ovalues, related_classname);
db->get(id, classname, related_classname, oresults);
assert(oresults == ovalues, "storing/retrieving object relationship");
db->get(id, classname, all_relationships);
assert(all_relationships[related_classname] == ovalues, "storing/retrieving all object relationships");
// now test backwards finding of relation
oresults.clear();
db->get(4, related_classname, classname, oresults);
assert((oresults.size() == 1 && oresults[0] == id), "retrieving object relationships backwards");
// test deleting values
svalues.remove("foo");
sresults.clear();
SarVector<string> toremove;
toremove << "foo";
db->del(id, classname, toremove, STRING);
db->get(id, classname, sresults);
assert(sresults == svalues, "deleting string value");
ivalues.remove("zoop");
iresults.clear();
toremove.clear();
toremove << "zoop";
db->del(id, classname, toremove, INTEGER);
db->get(id, classname, iresults);
assert(iresults == ivalues, "deleting int value");
// test deleting association
SarVector<int> itoremove;
itoremove << 4;
ovalues.remove(4);
oresults.clear();
db->del(id, classname, itoremove, related_classname);
db->get(id, classname, related_classname, oresults);
assert(oresults == ovalues, "deleting object relationship");
// test searching
// get all
oresults.clear();
db->get(classname, oresults);
assert((oresults.size() == 1 && oresults[0] == id), "getting all objects of a type");
// get all with string value
oresults.clear();
db->get(classname, "baz", "foo", oresults);
assert((oresults.size() == 1 && oresults[0] == id), "getting all objects with matching string prop value");
// get all with int value
oresults.clear();
db->get(classname, "bar", 998, oresults);
assert((oresults.size() == 1 && oresults[0] == id), "getting all objects with matching int prop value");
// test delete record
db->delete_record(id, classname);
oresults.clear();
db->get(classname, oresults);
assert((oresults.size() == 0), "deleting one object");
// test delete all records
db->set(id, classname, svalues, true);
oresults.clear();
db->delete_records(classname);
db->get(classname, oresults);
assert((oresults.size() == 0), "deleting all objects of a type");
delete Sar_Dbi::dbi;
debug("If you're at this point, no errors were found.");
return 0;
}
<commit_msg>added more output in db test<commit_after>#include "../stactive_record.h"
using namespace stactiverecord;
Sar_Dbi * Sar_Dbi::dbi = Sar_Dbi::makeStorage("sqlite://./sqlitedb.db");
void assert(bool v, string msg) {
if(v) return;
throw Sar_AssertionFailedException("Failed when testing " + msg);
}
int main() {
debug("Testing sqlite...");
Sar_Dbi *db = Sar_Dbi::dbi;
string classname = "testclass";
string related_classname = "testclass_related";
// recreate tables;
db->initialize_tables(classname);
// test id creation
debug("testing id creation");
assert(db->next_id(classname) == 0, "next_id incrementing");
assert(db->next_id(classname) == 1, "next_id incrementing");
assert(db->next_id(classname) == 2, "next_id incrementing");
assert(db->current_id(classname) == 2, "getting current id");
int id = 2;
SarMap<string> svalues;
SarMap<int> ivalues;
SarMap<string> sresults;
SarMap<int> iresults;
SarVector<int> ovalues;
SarVector<int> oresults;
SarMap< SarVector<int> > all_relationships;
// test inserts
debug("testing inserts");
svalues["foo"] = "bar";
svalues["baz"] = "bang";
ivalues["bar"] = 55;
ivalues["zoop"] = 1234;
db->set(id, classname, svalues, true);
db->set(id, classname, ivalues, true);
db->get(id, classname, sresults);
db->get(id, classname, iresults);
assert(sresults == svalues, "storing/retrieving string values");
assert(iresults == ivalues, "storing/retrieving int values");
// now test updates
debug("testing updates");
svalues["foo"] = "oof";
svalues["baz"] = "foo";
ivalues["bar"] = 998;
ivalues["zoop"] = 5364;
db->set(id, classname, svalues, false);
db->set(id, classname, ivalues, false);
sresults.clear();
iresults.clear();
db->get(id, classname, sresults);
db->get(id, classname, iresults);
assert(sresults == svalues, "updating/retrieving string values");
assert(iresults == ivalues, "updating/retrieving int values");
// now test record relations
debug("testing record relations");
ovalues << 4;
ovalues << 5;
ovalues << 6;
db->set(id, classname, ovalues, related_classname);
db->get(id, classname, related_classname, oresults);
assert(oresults == ovalues, "storing/retrieving object relationship");
db->get(id, classname, all_relationships);
assert(all_relationships[related_classname] == ovalues, "storing/retrieving all object relationships");
// now test backwards finding of relation
debug("test backwards finding of relation");
oresults.clear();
db->get(4, related_classname, classname, oresults);
assert((oresults.size() == 1 && oresults[0] == id), "retrieving object relationships backwards");
// test deleting values
debug("testing deleting values");
svalues.remove("foo");
sresults.clear();
SarVector<string> toremove;
toremove << "foo";
db->del(id, classname, toremove, STRING);
db->get(id, classname, sresults);
assert(sresults == svalues, "deleting string value");
ivalues.remove("zoop");
iresults.clear();
toremove.clear();
toremove << "zoop";
db->del(id, classname, toremove, INTEGER);
db->get(id, classname, iresults);
assert(iresults == ivalues, "deleting int value");
// test deleting association
debug("testing deleting association");
SarVector<int> itoremove;
itoremove << 4;
ovalues.remove(4);
oresults.clear();
db->del(id, classname, itoremove, related_classname);
db->get(id, classname, related_classname, oresults);
assert(oresults == ovalues, "deleting object relationship");
// test searching
debug("testing searching");
// get all
oresults.clear();
db->get(classname, oresults);
assert((oresults.size() == 1 && oresults[0] == id), "getting all objects of a type");
// get all with string value
oresults.clear();
db->get(classname, "baz", "foo", oresults);
assert((oresults.size() == 1 && oresults[0] == id), "getting all objects with matching string prop value");
// get all with int value
oresults.clear();
db->get(classname, "bar", 998, oresults);
assert((oresults.size() == 1 && oresults[0] == id), "getting all objects with matching int prop value");
// test delete record
debug("testing deleting record");
db->delete_record(id, classname);
oresults.clear();
db->get(classname, oresults);
assert((oresults.size() == 0), "deleting one object");
// test delete all records
debug("testing deleting all records");
db->set(id, classname, svalues, true);
oresults.clear();
db->delete_records(classname);
db->get(classname, oresults);
assert((oresults.size() == 0), "deleting all objects of a type");
delete Sar_Dbi::dbi;
debug("If you're at this point, no errors were found.");
return 0;
}
<|endoftext|> |
<commit_before>#include <string>
#include <queue>
#include <iostream>
#include "tpunit++.hpp"
#include "fakeit.h"
#include "fakeit/FakeitExceptions.h"
using namespace fakeit;
using namespace std;
struct DemoTests
// : tpunit::TestFixture
{
DemoTests()
// :
// tpunit::TestFixture(
//
//TEST(DemoTests::basic_stubbing), //
//TEST(DemoTests::basic_verification) //
//
// )
{
}
struct SomeInterface {
virtual int foo(int) = 0;
virtual int bar(string) = 0;
virtual void proc(int) = 0;
};
void basic_stubbing() {
// Instantiate a mock object.
Mock<SomeInterface> mock;
// Setup mock behavior.
When(mock[&SomeInterface::foo]).AlwaysReturn(1);
auto agrument_a_is_even = [](int a){return a%2==0;};
When(mock[&SomeInterface::foo].Matching(agrument_a_is_even)).Return(0);
// Fetch the mock instance.
SomeInterface &i = mock.get();
int a = i.foo(1);
int a1 = i.foo(2);
int a2 = i.foo(3);
// Will print "1".
cout << i.foo(0);
}
void basic_verification() {
Mock<SomeInterface> mock;
//
When(mock[&SomeInterface::foo]).AlwaysReturn(0);
When(mock[&SomeInterface::bar]).AlwaysReturn(0);
SomeInterface &i = mock.get();
// Production code
i.foo(1);
i.bar("some value");
// Verify for foo & bar where invoked
Verify(mock[&SomeInterface::foo]);
Verify(mock[&SomeInterface::bar]);
// Verify for foo & bar where invoked with specific arguments
Verify(mock[&SomeInterface::foo].Using(1));
Verify(mock[&SomeInterface::bar].Using("some value"));
// Verify for foo & bar where never invoked with other arguments
Verify(mock[&SomeInterface::foo].Using(2)).Never();
Verify(mock[&SomeInterface::bar].Using("some other value")).Never();
}//
} __DemoTests;
<commit_msg>make a change to trigger build<commit_after>#include <string>
#include <queue>
#include <iostream>
#include "tpunit++.hpp"
#include "fakeit.h"
#include "fakeit/FakeitExceptions.h"
using namespace fakeit;
using namespace std;
struct DemoTests
// : tpunit::TestFixture
{
DemoTests()
// :
// tpunit::TestFixture(
//
//TEST(DemoTests::basic_stubbing), //
//TEST(DemoTests::basic_verification) //
//
// )
{
}
struct SomeInterface {
virtual int foo(int) = 0;
virtual int bar(string) = 0;
virtual void proc(int) = 0;
};
void basic_stubbing() {
// Instantiate a mock object.
Mock<SomeInterface> mock;
// Setup mock behavior.
When(mock[&SomeInterface::foo]).AlwaysReturn(1);
auto agrument_a_is_even = [](int a){return a%2==0;};
When(mock[&SomeInterface::foo].Matching(agrument_a_is_even)).Return(0);
// Fetch the mock instance.
SomeInterface &i = mock.get();
int a = i.foo(1);
int a1 = i.foo(2);
int a2 = i.foo(3);
//
// Will print "1".
cout << i.foo(0);
}
void basic_verification() {
Mock<SomeInterface> mock;
//
When(mock[&SomeInterface::foo]).AlwaysReturn(0);
When(mock[&SomeInterface::bar]).AlwaysReturn(0);
SomeInterface &i = mock.get();
// Production code
i.foo(1);
i.bar("some value");
// Verify for foo & bar where invoked
Verify(mock[&SomeInterface::foo]);
Verify(mock[&SomeInterface::bar]);
// Verify for foo & bar where invoked with specific arguments
Verify(mock[&SomeInterface::foo].Using(1));
Verify(mock[&SomeInterface::bar].Using("some value"));
// Verify for foo & bar where never invoked with other arguments
Verify(mock[&SomeInterface::foo].Using(2)).Never();
Verify(mock[&SomeInterface::bar].Using("some other value")).Never();
}//
} __DemoTests;
<|endoftext|> |
<commit_before>#include <x0/source.hpp>
#include <x0/file_source.hpp>
#include <x0/sink.hpp>
#include <x0/file_sink.hpp>
#include <x0/filter.hpp>
#include <x0/null_filter.hpp>
#include <x0/uppercase_filter.hpp>
#include <x0/compress_filter.hpp>
#include <x0/chain_filter.hpp>
#include <x0/pump.hpp>
#include <iostream>
#include <memory>
int main(int argc, const char *argv[])
{
if (argc != 3 && argc != 4)
{
std::cerr << "usage: " << argv[0] << " INPUT OUTPUT [-u]" << std::endl;
std::cerr << " where INPUT and OUTPUT can be '-' to be interpreted as stdin/stdout respectively." << std::endl;
return 1;
}
std::string ifn(argv[1]);
std::shared_ptr<x0::source> input(ifn == "-"
? new x0::fd_source(STDIN_FILENO)
: new x0::file_source(ifn)
);
std::string ofn(argv[2]);
std::shared_ptr<x0::sink> output(ofn == "-"
? new x0::fd_sink(STDOUT_FILENO)
: new x0::file_sink(ofn)
);
if (argc >= 4)
{
x0::chain_filter cf;
if (std::string(argv[3]) == "-u")
cf.push_back(x0::filter_ptr(new x0::uppercase_filter()));
else if (std::string(argv[3]) == "-d")
cf.push_back(x0::filter_ptr(new x0::compress_filter()));
pump(*input, *output, cf);
}
else
{
pump(*input, *output);
}
return 0;
}
<commit_msg>io_copy (I/O filtering) test tool improved<commit_after>#include <x0/source.hpp>
#include <x0/file_source.hpp>
#include <x0/sink.hpp>
#include <x0/file_sink.hpp>
#include <x0/filter.hpp>
#include <x0/null_filter.hpp>
#include <x0/uppercase_filter.hpp>
#include <x0/compress_filter.hpp>
#include <x0/chain_filter.hpp>
#include <x0/pump.hpp>
#include <iostream>
#include <memory>
#include <getopt.h>
int main(int argc, char *argv[])
{
struct option options[] = {
{ "input", required_argument, 0, 'i' },
{ "output", required_argument, 0, 'o' },
{ "gzip", no_argument, 0, 'c' },
{ "uppercase", no_argument, 0, 'U' },
{ "help", no_argument, 0, 'h' },
{ 0, 0, 0, 0 }
};
std::string ifname("-");
std::string ofname("-");
x0::chain_filter cf;
for (bool done = false; !done; )
{
int index = 0;
int rv = (getopt_long(argc, argv, "i:o:hUc", options, &index));
switch (rv)
{
case 'i':
ifname = optarg;
break;
case 'o':
ofname = optarg;
break;
case 'U':
cf.push_back(x0::filter_ptr(new x0::uppercase_filter()));
break;
case 'c':
cf.push_back(x0::filter_ptr(new x0::compress_filter()));
break;
case 'h':
std::cerr
<< "usage: " << argv[0] << " INPUT OUTPUT [-u]" << std::endl
<< " where INPUT and OUTPUT can be '-' to be interpreted as stdin/stdout respectively." << std::endl;
return 0;
case 0:
break;
case -1:
done = true;
break;
default:
std::cerr << "syntax error: "
<< "(" << rv << ")" << std::endl;
return 1;
}
}
std::shared_ptr<x0::source> input(ifname == "-"
? new x0::fd_source(STDIN_FILENO)
: new x0::file_source(ifname)
);
std::shared_ptr<x0::sink> output(ofname == "-"
? new x0::fd_sink(STDOUT_FILENO)
: new x0::file_sink(ofname)
);
pump(*input, *output, cf);
return 0;
}
<|endoftext|> |
<commit_before>#include <iostream>
#include <algorithm>
#include <fstream>
#include "catch.h"
#include "../include/NeuralNet.h"
#include "../include/Pruner.h"
#include "../include/Backpropagation.h"
// Constants set for testing, could be anything
const static double ERROR_ALLOWANCE = 0.1;
const static int HIDDEN_LAYERS(1);
const static int NEURONS(10);
const static std::vector< std::vector<double> > input = { {1}, {2}, {3} };
const static std::vector< std::vector<double> > correctOutput = { {2}, {4}, {6} };
TEST_CASE("Test pruning", "[pruner]") {
srand(time(NULL));
net::Pruner pruner;
double error1, error2;
for(unsigned int a = 0; a < 200; a++) {
std::cout << a << ", " << error1 << ", " << error2 << "\n";
net::NeuralNet neuralNetwork1(input[0].size(), correctOutput[0].size(), HIDDEN_LAYERS, NEURONS, "sigmoid");
neuralNetwork1.setOutputActivationFunction("simpleLinear");
net::NeuralNet neuralNetwork2(neuralNetwork1);
net::Backpropagation initialTrainer = net::Backpropagation(0.1, 0.9, 0.01, 10000);
initialTrainer.train(&neuralNetwork1, input, correctOutput);
initialTrainer.train(&neuralNetwork2, input, correctOutput);
pruner.prune(&neuralNetwork1, &initialTrainer);
pruner.pruneRandomnly(&neuralNetwork2);
net::Backpropagation quickTrainer = net::Backpropagation(0.1, 0.9, 0.00, 50);
quickTrainer.train(&neuralNetwork1, input, correctOutput);
quickTrainer.train(&neuralNetwork2, input, correctOutput);
for(const auto ¤t: input) {
error1 += fabs(current[0]*2 - neuralNetwork1.getOutput(current)[0]);
error2 += fabs(current[0]*2 - neuralNetwork2.getOutput(current)[0]);
}
}
REQUIRE(error1 < error2);
}
<commit_msg>Pruning test more stable<commit_after>#include <iostream>
#include <algorithm>
#include <fstream>
#include "catch.h"
#include "../include/NeuralNet.h"
#include "../include/Pruner.h"
#include "../include/Backpropagation.h"
// Constants set for testing, could be anything
const static double ERROR_ALLOWANCE = 0.1;
const static int HIDDEN_LAYERS(1);
const static int NEURONS(10);
const static std::vector< std::vector<double> > input = { {1}, {2}, {3} };
const static std::vector< std::vector<double> > correctOutput = { {2}, {4}, {6} };
TEST_CASE("Test pruning", "[pruner]") {
srand(time(NULL));
net::Pruner pruner;
double error1, error2;
for(unsigned int a = 0; a < 1000; a++) {
std::cout << a << ", " << error1 << ", " << error2 << "\n";
net::NeuralNet neuralNetwork1(input[0].size(), correctOutput[0].size(), HIDDEN_LAYERS, NEURONS, "sigmoid");
neuralNetwork1.setOutputActivationFunction("simpleLinear");
net::NeuralNet neuralNetwork2(neuralNetwork1);
net::Backpropagation initialTrainer = net::Backpropagation(0.1, 0.9, 0.01, 10000);
initialTrainer.train(&neuralNetwork1, input, correctOutput);
initialTrainer.train(&neuralNetwork2, input, correctOutput);
pruner.prune(&neuralNetwork1, &initialTrainer);
pruner.pruneRandomnly(&neuralNetwork2);
net::Backpropagation quickTrainer = net::Backpropagation(0.1, 0.9, 0.00, 50);
quickTrainer.train(&neuralNetwork1, input, correctOutput);
quickTrainer.train(&neuralNetwork2, input, correctOutput);
for(const auto ¤t: input) {
error1 += fabs(current[0]*2 - neuralNetwork1.getOutput(current)[0]);
error2 += fabs(current[0]*2 - neuralNetwork2.getOutput(current)[0]);
}
}
REQUIRE((error2 - error1) / error2) < 0.1);
}
<|endoftext|> |
<commit_before>#define BOOST_TEST_MODULE StencilConvolution
#include <boost/test/unit_test.hpp>
#include "context_setup.hpp"
BOOST_AUTO_TEST_CASE(stencil_convolution)
{
const int n = 1024;
std::vector<double> s = random_vector<double>(rand() % 64 + 1);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s, center);
std::vector<double> x = random_vector<double>(n);
std::generate(x.begin(), x.end(), [](){ return (double)rand() / RAND_MAX; });
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = 1;
Y += X * S;
check_sample(Y, [&](int i, double a) {
double sum = 1;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, sum, 1e-8);
});
Y = 42 * (X * S);
check_sample(Y, [&](int i, double a) {
double sum = 0;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, 42 * sum, 1e-8);
});
}
#if BOOST_VERSION >= 105000
// Boost upto v1.49 segfoults on this test
BOOST_AUTO_TEST_CASE(two_stencils)
{
const int n = 32;
std::vector<double> s(5, 1);
vex::stencil<double> S(ctx, s, 3);
vex::vector<double> X(ctx, n);
vex::vector<double> Y(ctx, n);
X = 0;
Y = X * S + X * S;
BOOST_CHECK(Y[ 0] == 0);
BOOST_CHECK(Y[16] == 0);
BOOST_CHECK(Y[31] == 0);
}
#endif
BOOST_AUTO_TEST_CASE(small_vector)
{
const int n = 128;
std::vector<double> s = random_vector<double>(rand() % 64 + 1);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s, center);
std::vector<double> x = random_vector<double>(n);
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = 1;
Y += X * S;
check_sample(Y, [&](int i, double a) {
double sum = 1;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, sum, 1e-8);
});
}
BOOST_AUTO_TEST_CASE(multivector)
{
typedef std::array<double, 2> elem_t;
const int n = 1024;
std::vector<double> s = random_vector<double>(rand() % 64 + 1);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s.begin(), s.end(), center);
std::vector<double> x = random_vector<double>(2 * n);
vex::multivector<double,2> X(ctx, x);
vex::multivector<double,2> Y(ctx, n);
Y = 1;
Y += X * S;
check_sample(Y, [&](int i, elem_t a) {
double sum[2] = {1, 1};
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++) {
sum[0] += s[j] * x[0 + std::min(n - 1, std::max(0, i + k))];
sum[1] += s[j] * x[n + std::min(n - 1, std::max(0, i + k))];
}
BOOST_CHECK_CLOSE(a[0], sum[0], 1e-8);
BOOST_CHECK_CLOSE(a[1], sum[1], 1e-8);
});
Y = 42 * (X * S);
check_sample(Y, [&](int i, elem_t a) {
double sum[2] = {0, 0};
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++) {
sum[0] += s[j] * x[0 + std::min(n - 1, std::max(0, i + k))];
sum[1] += s[j] * x[n + std::min(n - 1, std::max(0, i + k))];
}
BOOST_CHECK_CLOSE(a[0], 42 * sum[0], 1e-8);
BOOST_CHECK_CLOSE(a[1], 42 * sum[1], 1e-8);
});
}
BOOST_AUTO_TEST_CASE(big_stencil)
{
const int n = 1 << 16;
std::vector<double> s = random_vector<double>(2048);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s, center);
std::vector<double> x = random_vector<double>(n);
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = X * S;
check_sample(Y, [&](int i, double a) {
double sum = 0;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, sum, 1e-8);
});
}
BOOST_AUTO_TEST_CASE(user_defined_stencil)
{
const int n = 1024;
VEX_STENCIL_OPERATOR(oscillate,
double, 3, 1, "return sin(X[1] - X[0]) + sin(X[0] - X[-1]);",
ctx);
std::vector<double> x = random_vector<double>(n);
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = oscillate(X);
check_sample(Y, [&](int i, double a) {
int left = std::max(0, i - 1);
int right = std::min(n - 1, i + 1);
double s = sin(x[right] - x[i]) + sin(x[i] - x[left]);
BOOST_CHECK_CLOSE(a, s, 1e-8);
});
Y = 41 * oscillate(X) + oscillate(X);
check_sample(Y, [&](int i, double a) {
int left = std::max(0, i - 1);
int right = std::min(n - 1, i + 1);
double s = sin(x[right] - x[i]) + sin(x[i] - x[left]);
BOOST_CHECK_CLOSE(a, 42 * s, 1e-8);
});
}
BOOST_AUTO_TEST_SUITE_END()
<commit_msg>Omit part of user_defined_stencil test for broken Boost versions<commit_after>#define BOOST_TEST_MODULE StencilConvolution
#include <boost/test/unit_test.hpp>
#include "context_setup.hpp"
BOOST_AUTO_TEST_CASE(stencil_convolution)
{
const int n = 1024;
std::vector<double> s = random_vector<double>(rand() % 64 + 1);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s, center);
std::vector<double> x = random_vector<double>(n);
std::generate(x.begin(), x.end(), [](){ return (double)rand() / RAND_MAX; });
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = 1;
Y += X * S;
check_sample(Y, [&](int i, double a) {
double sum = 1;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, sum, 1e-8);
});
Y = 42 * (X * S);
check_sample(Y, [&](int i, double a) {
double sum = 0;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, 42 * sum, 1e-8);
});
}
#if BOOST_VERSION >= 105000
// Boost upto v1.49 segfoults on this test
BOOST_AUTO_TEST_CASE(two_stencils)
{
const int n = 32;
std::vector<double> s(5, 1);
vex::stencil<double> S(ctx, s, 3);
vex::vector<double> X(ctx, n);
vex::vector<double> Y(ctx, n);
X = 0;
Y = X * S + X * S;
BOOST_CHECK(Y[ 0] == 0);
BOOST_CHECK(Y[16] == 0);
BOOST_CHECK(Y[31] == 0);
}
#endif
BOOST_AUTO_TEST_CASE(small_vector)
{
const int n = 128;
std::vector<double> s = random_vector<double>(rand() % 64 + 1);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s, center);
std::vector<double> x = random_vector<double>(n);
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = 1;
Y += X * S;
check_sample(Y, [&](int i, double a) {
double sum = 1;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, sum, 1e-8);
});
}
BOOST_AUTO_TEST_CASE(multivector)
{
typedef std::array<double, 2> elem_t;
const int n = 1024;
std::vector<double> s = random_vector<double>(rand() % 64 + 1);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s.begin(), s.end(), center);
std::vector<double> x = random_vector<double>(2 * n);
vex::multivector<double,2> X(ctx, x);
vex::multivector<double,2> Y(ctx, n);
Y = 1;
Y += X * S;
check_sample(Y, [&](int i, elem_t a) {
double sum[2] = {1, 1};
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++) {
sum[0] += s[j] * x[0 + std::min(n - 1, std::max(0, i + k))];
sum[1] += s[j] * x[n + std::min(n - 1, std::max(0, i + k))];
}
BOOST_CHECK_CLOSE(a[0], sum[0], 1e-8);
BOOST_CHECK_CLOSE(a[1], sum[1], 1e-8);
});
Y = 42 * (X * S);
check_sample(Y, [&](int i, elem_t a) {
double sum[2] = {0, 0};
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++) {
sum[0] += s[j] * x[0 + std::min(n - 1, std::max(0, i + k))];
sum[1] += s[j] * x[n + std::min(n - 1, std::max(0, i + k))];
}
BOOST_CHECK_CLOSE(a[0], 42 * sum[0], 1e-8);
BOOST_CHECK_CLOSE(a[1], 42 * sum[1], 1e-8);
});
}
BOOST_AUTO_TEST_CASE(big_stencil)
{
const int n = 1 << 16;
std::vector<double> s = random_vector<double>(2048);
int center = rand() % s.size();
vex::stencil<double> S(ctx, s, center);
std::vector<double> x = random_vector<double>(n);
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = X * S;
check_sample(Y, [&](int i, double a) {
double sum = 0;
size_t j = 0;
int k = -center;
for(; j < s.size(); k++, j++)
sum += s[j] * x[std::min(n - 1, std::max(0, i + k))];
BOOST_CHECK_CLOSE(a, sum, 1e-8);
});
}
BOOST_AUTO_TEST_CASE(user_defined_stencil)
{
const int n = 1024;
VEX_STENCIL_OPERATOR(oscillate,
double, 3, 1, "return sin(X[1] - X[0]) + sin(X[0] - X[-1]);",
ctx);
std::vector<double> x = random_vector<double>(n);
vex::vector<double> X(ctx, x);
vex::vector<double> Y(ctx, n);
Y = oscillate(X);
check_sample(Y, [&](int i, double a) {
int left = std::max(0, i - 1);
int right = std::min(n - 1, i + 1);
double s = sin(x[right] - x[i]) + sin(x[i] - x[left]);
BOOST_CHECK_CLOSE(a, s, 1e-8);
});
#if BOOST_VERSION >= 105000
Y = 41 * oscillate(X) + oscillate(X);
check_sample(Y, [&](int i, double a) {
int left = std::max(0, i - 1);
int right = std::min(n - 1, i + 1);
double s = sin(x[right] - x[i]) + sin(x[i] - x[left]);
BOOST_CHECK_CLOSE(a, 42 * s, 1e-8);
});
#endif
}
BOOST_AUTO_TEST_SUITE_END()
<|endoftext|> |
<commit_before>/*
* Copyright (c) 2008-2018 SLIBIO <https://github.com/SLIBIO>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "slib/ui/adapter.h"
#include "slib/ui/linear_view.h"
namespace slib
{
SLIB_DEFINE_OBJECT(ViewAdapter, Object)
ViewAdapter::ViewAdapter()
{
}
ViewAdapter::~ViewAdapter()
{
}
sl_ui_len ViewAdapter::getAverageItemHeight(View* parent)
{
return 0;
}
void ViewAdapter::populateInto(View* parent, UIUpdateMode mode)
{
if (!parent) {
return;
}
UIUpdateMode _mode = SLIB_UI_UPDATE_MODE_IS_INIT(mode) ? UIUpdateMode::Init : UIUpdateMode::None;
sl_uint64 n = getItemsCount();
for (sl_uint64 i = 0; i < n; i++) {
Ref<View> view = getView(i, sl_null, parent);
if (view.isNotNull()) {
parent->addChild(view, _mode);
}
}
parent->invalidateLayout(mode);
}
void ViewAdapter::populateInto(const Ref<View>& parent, UIUpdateMode mode)
{
populateInto(parent.get(), mode);
}
SLIB_DEFINE_OBJECT(ViewListAdapter, ViewAdapter)
ViewListAdapter::ViewListAdapter()
{
}
ViewListAdapter::~ViewListAdapter()
{
}
ViewListAdapter::ViewListAdapter(const List< Ref<View> >& list): m_list(list)
{
}
Ref<ViewListAdapter> ViewListAdapter::create(const List< Ref<View> >& list)
{
return new ViewListAdapter(list);
}
List< Ref<View> > ViewListAdapter::getList()
{
return m_list;
}
void ViewListAdapter::setList(const List< Ref<View> >& list)
{
m_list = list;
}
void ViewListAdapter::addView(const Ref<View>& view)
{
m_list.add(view);
}
sl_uint64 ViewListAdapter::getItemsCount()
{
return m_list.getCount();
}
Ref<View> ViewListAdapter::getView(sl_uint64 index, View* original, View* parent)
{
return m_list.getValueAt((sl_size)index);
}
SLIB_DEFINE_OBJECT(ViewRowAdapter, ViewAdapter)
ViewRowAdapter::ViewRowAdapter()
: m_nColumns(1)
{
}
ViewRowAdapter::~ViewRowAdapter()
{
}
Ref<ViewRowAdapter> ViewRowAdapter::create(sl_uint32 nColumns, const Ref<ViewAdapter>& itemAdapter)
{
if (itemAdapter.isNull()) {
return sl_null;
}
if (nColumns < 1) {
return sl_null;
}
Ref<ViewRowAdapter> ret = new ViewRowAdapter;
if (ret.isNotNull()) {
ret->m_nColumns = nColumns;
ret->m_itemAdapter = itemAdapter;
return ret;
}
return sl_null;
}
sl_uint32 ViewRowAdapter::getColumnsCount()
{
return m_nColumns;
}
void ViewRowAdapter::setColumnsCount(sl_uint32 nColumns)
{
m_nColumns = nColumns;
}
Ref<ViewAdapter> ViewRowAdapter::getItemAdapter()
{
return m_itemAdapter;
}
void ViewRowAdapter::setItemAdapter(const Ref<ViewAdapter>& adapter)
{
m_itemAdapter = adapter;
}
sl_uint64 ViewRowAdapter::getItemsCount()
{
Ref<ViewAdapter> adapter = m_itemAdapter;
if (adapter.isNotNull()) {
sl_uint32 m = m_nColumns;
if (m >= 1) {
sl_uint64 n = adapter->getItemsCount();
sl_uint64 r = n / m;
if (n % m) {
r++;
}
return r;
}
}
return 0;
}
Ref<View> ViewRowAdapter::getView(sl_uint64 index, View* original, View* parent)
{
Ref<ViewAdapter> adapter = m_itemAdapter;
if (adapter.isNotNull()) {
sl_uint32 m = m_nColumns;
if (m >= 1) {
sl_uint64 nTotal = adapter->getItemsCount();
sl_uint64 start = index * m;
sl_uint32 n = m;
if (start + n > nTotal) {
n = (sl_uint32)(nTotal - start);
}
Ref<LinearView> group = (LinearView*)original;
sl_bool flagNewGroup = sl_false;
if (group.isNull()) {
group = new LinearView;
if (group.isNull()) {
return sl_null;
}
group->setOrientation(LayoutOrientation::Horizontal, UIUpdateMode::Init);
group->setWidthFilling(1.0f, UIUpdateMode::Init);
group->setHeightWrapping(UIUpdateMode::Init);
flagNewGroup = sl_true;
}
sl_bool flagRebuild = sl_false;
Queue< Ref<View> > children;
for (sl_uint32 i = 0; i < n; i++) {
Ref<View> child = group->getChild(i);
Ref<View> childNew = adapter->getView(start + i, child.get(), group.get());
if (child != childNew) {
flagRebuild = sl_true;
}
if (childNew.isNotNull()) {
children.push_NoLock(childNew);
}
}
sl_size nChildren = group->getChildrenCount();
if (flagRebuild || nChildren != children.getCount()) {
if (nChildren) {
group->removeAllChildren(UIUpdateMode::None);
}
for (auto& child : children) {
group->addChild(child, flagNewGroup ? UIUpdateMode::Init : UIUpdateMode::None);
}
if (!flagNewGroup) {
group->invalidateLayout();
}
}
return group;
}
}
return sl_null;
}
sl_ui_len ViewRowAdapter::getAverageItemHeight(View* parent)
{
Ref<ViewAdapter> adapter = m_itemAdapter;
if (adapter.isNotNull()) {
return adapter->getAverageItemHeight(parent);
}
return ViewAdapter::getAverageItemHeight(parent);
}
}
<commit_msg>ui/ListView: improved ListView performance by adding `getItemHeight()` at adapter<commit_after>/*
* Copyright (c) 2008-2018 SLIBIO <https://github.com/SLIBIO>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "slib/ui/adapter.h"
#include "slib/ui/linear_view.h"
namespace slib
{
SLIB_DEFINE_OBJECT(ViewAdapter, Object)
ViewAdapter::ViewAdapter()
{
}
ViewAdapter::~ViewAdapter()
{
}
sl_ui_len ViewAdapter::getAverageItemHeight(View* parent)
{
return 0;
}
sl_ui_len ViewAdapter::getItemHeight(sl_uint64 index, View* parent)
{
return 0;
}
void ViewAdapter::populateInto(View* parent, UIUpdateMode mode)
{
if (!parent) {
return;
}
UIUpdateMode _mode = SLIB_UI_UPDATE_MODE_IS_INIT(mode) ? UIUpdateMode::Init : UIUpdateMode::None;
sl_uint64 n = getItemsCount();
for (sl_uint64 i = 0; i < n; i++) {
Ref<View> view = getView(i, sl_null, parent);
if (view.isNotNull()) {
parent->addChild(view, _mode);
}
}
parent->invalidateLayout(mode);
}
void ViewAdapter::populateInto(const Ref<View>& parent, UIUpdateMode mode)
{
populateInto(parent.get(), mode);
}
SLIB_DEFINE_OBJECT(ViewListAdapter, ViewAdapter)
ViewListAdapter::ViewListAdapter()
{
}
ViewListAdapter::~ViewListAdapter()
{
}
ViewListAdapter::ViewListAdapter(const List< Ref<View> >& list): m_list(list)
{
}
Ref<ViewListAdapter> ViewListAdapter::create(const List< Ref<View> >& list)
{
return new ViewListAdapter(list);
}
List< Ref<View> > ViewListAdapter::getList()
{
return m_list;
}
void ViewListAdapter::setList(const List< Ref<View> >& list)
{
m_list = list;
}
void ViewListAdapter::addView(const Ref<View>& view)
{
m_list.add(view);
}
sl_uint64 ViewListAdapter::getItemsCount()
{
return m_list.getCount();
}
Ref<View> ViewListAdapter::getView(sl_uint64 index, View* original, View* parent)
{
return m_list.getValueAt((sl_size)index);
}
SLIB_DEFINE_OBJECT(ViewRowAdapter, ViewAdapter)
ViewRowAdapter::ViewRowAdapter()
: m_nColumns(1)
{
}
ViewRowAdapter::~ViewRowAdapter()
{
}
Ref<ViewRowAdapter> ViewRowAdapter::create(sl_uint32 nColumns, const Ref<ViewAdapter>& itemAdapter)
{
if (itemAdapter.isNull()) {
return sl_null;
}
if (nColumns < 1) {
return sl_null;
}
Ref<ViewRowAdapter> ret = new ViewRowAdapter;
if (ret.isNotNull()) {
ret->m_nColumns = nColumns;
ret->m_itemAdapter = itemAdapter;
return ret;
}
return sl_null;
}
sl_uint32 ViewRowAdapter::getColumnsCount()
{
return m_nColumns;
}
void ViewRowAdapter::setColumnsCount(sl_uint32 nColumns)
{
m_nColumns = nColumns;
}
Ref<ViewAdapter> ViewRowAdapter::getItemAdapter()
{
return m_itemAdapter;
}
void ViewRowAdapter::setItemAdapter(const Ref<ViewAdapter>& adapter)
{
m_itemAdapter = adapter;
}
sl_uint64 ViewRowAdapter::getItemsCount()
{
Ref<ViewAdapter> adapter = m_itemAdapter;
if (adapter.isNotNull()) {
sl_uint32 m = m_nColumns;
if (m >= 1) {
sl_uint64 n = adapter->getItemsCount();
sl_uint64 r = n / m;
if (n % m) {
r++;
}
return r;
}
}
return 0;
}
Ref<View> ViewRowAdapter::getView(sl_uint64 index, View* original, View* parent)
{
Ref<ViewAdapter> adapter = m_itemAdapter;
if (adapter.isNotNull()) {
sl_uint32 m = m_nColumns;
if (m >= 1) {
sl_uint64 nTotal = adapter->getItemsCount();
sl_uint64 start = index * m;
sl_uint32 n = m;
if (start + n > nTotal) {
n = (sl_uint32)(nTotal - start);
}
Ref<LinearView> group = (LinearView*)original;
sl_bool flagNewGroup = sl_false;
if (group.isNull()) {
group = new LinearView;
if (group.isNull()) {
return sl_null;
}
group->setOrientation(LayoutOrientation::Horizontal, UIUpdateMode::Init);
group->setWidthFilling(1.0f, UIUpdateMode::Init);
group->setHeightWrapping(UIUpdateMode::Init);
flagNewGroup = sl_true;
}
sl_bool flagRebuild = sl_false;
Queue< Ref<View> > children;
for (sl_uint32 i = 0; i < n; i++) {
Ref<View> child = group->getChild(i);
Ref<View> childNew = adapter->getView(start + i, child.get(), group.get());
if (child != childNew) {
flagRebuild = sl_true;
}
if (childNew.isNotNull()) {
children.push_NoLock(childNew);
}
}
sl_size nChildren = group->getChildrenCount();
if (flagRebuild || nChildren != children.getCount()) {
if (nChildren) {
group->removeAllChildren(UIUpdateMode::None);
}
for (auto& child : children) {
group->addChild(child, flagNewGroup ? UIUpdateMode::Init : UIUpdateMode::None);
}
if (!flagNewGroup) {
group->invalidateLayout();
}
}
return group;
}
}
return sl_null;
}
sl_ui_len ViewRowAdapter::getAverageItemHeight(View* parent)
{
Ref<ViewAdapter> adapter = m_itemAdapter;
if (adapter.isNotNull()) {
return adapter->getAverageItemHeight(parent);
}
return ViewAdapter::getAverageItemHeight(parent);
}
}
<|endoftext|> |
<commit_before>#include "testhelper.hpp"
#include "../src/Xml/XmlParser.hpp"
#include "../src/Xsl/Xsl.hpp"
void
testXslTransform()
{
// xml
std::string xmlContent (xml_code(
<root>
rethdghg
<cd>
<title>Title A</title>
</cd>
<cd>
<title>Title B</title>
</cd>
</root>
));
Xml::Log xmlLog;
Xml::Document * xmlDoc = Xml::parse(xmlContent, &xmlLog);
// xsl
std::string xslContent (xml_code(
<xsl:stylesheet>
<xsl:template match="cd">
<xsl:value-of select="title" />
</xsl:template>
<xsl:template match="/">
<html>
<xsl:for-each select="cd">
<div>
<h1>This is a CD</h1>
<h2><xsl:value-of select="title" /></h2>
</div>
</xsl:for-each>
</html>
</xsl:template>
</xsl:stylesheet>
));
Xml::Log xslLog;
Xml::Document * xslDoc = Xml::parse(xslContent, &xslLog);
test_assert(xslDoc != 0);
test_assert(xmlDoc != 0);
Xml::Document* result = Xsl::xslTransform(*xmlDoc, *xslDoc);
std::cerr << "XSL output = " << std::endl << *result << std::endl;
delete xmlDoc;
delete xslDoc;
}
void
testGetTemplate()
{
// xml
std::string xmlContent (xml_code(
<catalog>
<cd>
<title>Title A</title>
<artist>Artist A</artist>
<category>Category A</category>
</cd>
<cd>
<title>Title B</title>
<artist>Artist B</artist>
<category>Category B</category>
</cd>
</catalog>
));
Xml::Log xmlLog;
Xml::Document * xmlDoc = Xml::parse(xmlContent, &xmlLog);
// xsl
std::string xslContent (xml_code(
<xsl:stylesheet>
<xsl:template match="cd">
DUMMY
</xsl:template>
<xsl:template match="catalog/cd">
<xsl:value-of select="title" /> - <xsl:value-of select="category" />
</xsl:template>
<xsl:template match="cd/title">
<xsl:value-of select="." />
</xsl:template>
<xsl:template match="category">
FirstTemplate
</xsl:template>
<xsl:template match="category">
LastTemplate
</xsl:template>
</xsl:stylesheet>
));
Xml::Log xslLog;
Xml::Document * xslDoc = Xml::parse(xslContent, &xslLog);
test_assert(xmlDoc != 0);
test_assert(xslDoc != 0);
const Xml::Element* cdElement = xmlDoc->root()->elements()[0];
const Xml::Element* titleElement = cdElement->elements("title")[0];
const Xml::Element* artistElement = cdElement->elements("artist")[0];
const Xml::Element* categoryElement = cdElement->elements("category")[0];
const Xml::Element* titleTemplate = Xsl::getTemplate(*xslDoc, titleElement);
test_assert(titleTemplate != nullptr);
test_assert(titleTemplate->attribute("match") == "cd/title");
const Xml::Element* cdTemplate = Xsl::getTemplate(*xslDoc, cdElement);
test_assert(cdTemplate != nullptr);
test_assert(cdTemplate->attribute("match") == "catalog/cd");
const Xml::Element* categoryTemplate = Xsl::getTemplate(*xslDoc, categoryElement);
test_assert(categoryTemplate != nullptr);
test_assert(categoryTemplate->children()[0]->contentText() == "LastTemplate");
const Xml::Element* artistTemplate = Xsl::getTemplate(*xslDoc, artistElement);
test_assert(artistTemplate == nullptr);
free(xmlDoc);
free(xslDoc);
}
int
main()
{
testXslTransform();
testGetTemplate();
return 0;
}
<commit_msg>Initiated a test for "value-of"<commit_after>#include "testhelper.hpp"
#include "../src/Xml/XmlParser.hpp"
#include "../src/Xsl/Xsl.hpp"
void
testXslTransform()
{
// xml
std::string xmlContent (xml_code(
<root>
rethdghg
<cd>
<title>Title A</title>
</cd>
<cd>
<title>Title B</title>
</cd>
</root>
));
Xml::Log xmlLog;
Xml::Document * xmlDoc = Xml::parse(xmlContent, &xmlLog);
// xsl
std::string xslContent (xml_code(
<xsl:stylesheet>
<xsl:template match="cd">
<xsl:value-of select="title" />
</xsl:template>
<xsl:template match="/">
<html>
<xsl:for-each select="cd">
<div>
<h1>This is a CD</h1>
<h2><xsl:value-of select="title" /></h2>
</div>
</xsl:for-each>
</html>
</xsl:template>
</xsl:stylesheet>
));
Xml::Log xslLog;
Xml::Document * xslDoc = Xml::parse(xslContent, &xslLog);
test_assert(xslDoc != 0);
test_assert(xmlDoc != 0);
Xml::Document* result = Xsl::xslTransform(*xmlDoc, *xslDoc);
std::cerr << "XSL output = " << std::endl << *result << std::endl;
delete xmlDoc;
delete xslDoc;
}
void
testGetTemplate()
{
// xml
std::string xmlContent (xml_code(
<catalog>
<cd>
<title>Title A</title>
<artist>Artist A</artist>
<category>Category A</category>
</cd>
<cd>
<title>Title B</title>
<artist>Artist B</artist>
<category>Category B</category>
</cd>
</catalog>
));
Xml::Log xmlLog;
Xml::Document * xmlDoc = Xml::parse(xmlContent, &xmlLog);
// xsl
std::string xslContent (xml_code(
<xsl:stylesheet>
<xsl:template match="cd">
DUMMY
</xsl:template>
<xsl:template match="catalog/cd">
<xsl:value-of select="title" /> - <xsl:value-of select="category" />
</xsl:template>
<xsl:template match="cd/title">
<xsl:value-of select="." />
</xsl:template>
<xsl:template match="category">
FirstTemplate
</xsl:template>
<xsl:template match="category">
LastTemplate
</xsl:template>
</xsl:stylesheet>
));
Xml::Log xslLog;
Xml::Document * xslDoc = Xml::parse(xslContent, &xslLog);
test_assert(xmlDoc != 0);
test_assert(xslDoc != 0);
const Xml::Element* cdElement = xmlDoc->root()->elements()[0];
const Xml::Element* titleElement = cdElement->elements("title")[0];
const Xml::Element* artistElement = cdElement->elements("artist")[0];
const Xml::Element* categoryElement = cdElement->elements("category")[0];
const Xml::Element* titleTemplate = Xsl::getTemplate(*xslDoc, titleElement);
test_assert(titleTemplate != nullptr);
test_assert(titleTemplate->attribute("match") == "cd/title");
const Xml::Element* cdTemplate = Xsl::getTemplate(*xslDoc, cdElement);
test_assert(cdTemplate != nullptr);
test_assert(cdTemplate->attribute("match") == "catalog/cd");
const Xml::Element* categoryTemplate = Xsl::getTemplate(*xslDoc, categoryElement);
test_assert(categoryTemplate != nullptr);
test_assert(categoryTemplate->children()[0]->contentText() == "LastTemplate");
const Xml::Element* artistTemplate = Xsl::getTemplate(*xslDoc, artistElement);
test_assert(artistTemplate == nullptr);
free(xmlDoc);
free(xslDoc);
}
void
testValueOf()
{
// xml
std::string xmlContent (xml_code(
<root>A<tag>B</tag>C</root>
));
Xml::Log xmlLog;
Xml::Document * xmlDoc = Xml::parse(xmlContent, &xmlLog);
// xsl
std::string xslContent (xml_code(
<xsl:stylesheet>
<xsl:template match="/">
<result><xsl:value-of select="." /></result>
</xsl:template>
</xsl:stylesheet>
));
Xml::Log xslLog;
Xml::Document * xslDoc = Xml::parse(xslContent, &xslLog);
test_assert(xslDoc != 0);
test_assert(xmlDoc != 0);
Xml::Document* result = Xsl::xslTransform(*xmlDoc, *xslDoc);
std::cerr << std::endl << *result->root()->elements()[0]->children()[0] << std::endl;
delete xmlDoc;
delete xslDoc;
}
int
main()
{
testXslTransform();
testGetTemplate();
testValueOf();
return 0;
}
<|endoftext|> |
<commit_before>// This is free and unencumbered software released into the public domain.
// For more information, please refer to <http://unlicense.org/>
#include "span_analyzer_frame.h"
#include "wx/aboutdlg.h"
#include "wx/xrc/xmlres.h"
#include "cable_file_manager_dialog.h"
#include "cable_unit_converter.h"
#include "file_handler.h"
#include "preferences_dialog.h"
#include "span_analyzer_app.h"
#include "span_analyzer_doc.h"
#include "span_analyzer_view.h"
#include "weather_load_case_manager_dialog.h"
#include "weather_load_case_unit_converter.h"
#include "../res/icon.xpm"
DocumentFileDropTarget::DocumentFileDropTarget(wxWindow* parent) {
parent_ = parent;
// creates data object to store dropped information
SetDataObject(new wxFileDataObject());
SetDefaultAction(wxDragCopy);
}
bool DocumentFileDropTarget::OnDropFiles(wxCoord x, wxCoord y,
const wxArrayString& filenames) {
// gets data from drag-and-drop operation
wxFileDataObject* data = (wxFileDataObject*)GetDataObject();
// tests if file exists
// only the first file in the list is processed
const wxString& str_file = data->GetFilenames().front();
if (wxFileName::Exists(str_file) == false) {
return false;
}
// tests if extension matches application document
wxFileName path(str_file);
if (path.GetExt() == ".spananalyzer") {
return false;
}
// freezes frame, opens document, and thaws frame
parent_->Freeze();
wxGetApp().manager_doc()->CreateDocument(str_file);
parent_->Thaw();
return true;
}
BEGIN_EVENT_TABLE(SpanAnalyzerFrame, wxFrame)
EVT_MENU(XRCID("menuitem_edit_cables"), SpanAnalyzerFrame::OnMenuEditCables)
EVT_MENU(XRCID("menuitem_edit_weathercases"), SpanAnalyzerFrame::OnMenuEditWeathercases)
EVT_MENU(XRCID("menuitem_file_preferences"), SpanAnalyzerFrame::OnMenuFilePreferences)
EVT_MENU(XRCID("menuitem_help_about"), SpanAnalyzerFrame::OnMenuHelpAbout)
EVT_MENU(XRCID("menuitem_view_log"), SpanAnalyzerFrame::OnMenuViewLog)
END_EVENT_TABLE()
SpanAnalyzerFrame::SpanAnalyzerFrame(wxDocManager* manager)
: wxDocParentFrame(manager, nullptr, wxID_ANY, "Span Analyzer") {
// loads dialog from virtual xrc file system
wxXmlResource::Get()->LoadMenuBar(this, "span_analyzer_menubar");
// sets the frame icon
SetIcon(wxIcon(icon_xpm));
// sets the drag and drop target
SetDropTarget(new DocumentFileDropTarget(this));
// tells aui manager to manage this frame
manager_.SetManagedWindow(this);
// creates log AUI window and adds to manager
wxAuiPaneInfo info;
info.Name("Log");
info.Float();
info.Caption("Log");
info.CloseButton(true);
info.Show(false);
pane_log_ = new LogPane(this);
manager_.AddPane(pane_log_, info);
manager_.Update();
}
SpanAnalyzerFrame::~SpanAnalyzerFrame() {
// saves frame size to application config
SpanAnalyzerConfig* config = wxGetApp().config();
if (this->IsMaximized() == true) {
config->size_frame = wxSize(0, 0);
} else {
config->size_frame = this->GetSize();
}
manager_.UnInit();
}
void SpanAnalyzerFrame::OnMenuEditCables(wxCommandEvent& event) {
// gets application config and data
const SpanAnalyzerConfig* config = wxGetApp().config();
SpanAnalyzerData* data = wxGetApp().data();
// creates and shows the cable file manager dialog
CableFileManagerDialog dialog(this, config->units, &data->cablefiles);
if (dialog.ShowModal() == wxID_OK) {
wxBusyCursor cursor;
// saves application data
FileHandler::SaveAppData(config->filepath_data, *data, config->units);
}
wxBusyCursor cursor;
// reloads all cable files in case things get out of sync
// i.e. user edits cable file, but doesn't accept any changes in file manager
// logs
wxLogMessage("Flushing cable files.");
for (auto iter = data->cablefiles.begin(); iter != data->cablefiles.end();
iter++) {
CableFile* cablefile = *iter;
FileHandler::LoadCable(cablefile->filepath, config->units,
cablefile->cable);
}
// updates document/views
SpanAnalyzerDoc* doc = (SpanAnalyzerDoc*)wxGetApp().manager_doc()->
GetCurrentDocument();
if (doc != nullptr) {
doc->RunAnalysis();
UpdateHint hint(HintType::kCablesEdit);
doc->UpdateAllViews(nullptr, &hint);
}
}
void SpanAnalyzerFrame::OnMenuEditWeathercases(
wxCommandEvent& event) {
// gets application data
SpanAnalyzerData* data = wxGetApp().data();
// shows an editor
WeatherLoadCaseManagerDialog dialog(
this,
wxGetApp().config()->units,
&data->groups_weathercase);
if (dialog.ShowModal() == wxID_OK) {
wxBusyCursor cursor;
// saves application data
FileHandler::SaveAppData(wxGetApp().config()->filepath_data, *data,
wxGetApp().config()->units);
// updates document/views
SpanAnalyzerDoc* doc = (SpanAnalyzerDoc*)wxGetApp().manager_doc()->
GetCurrentDocument();
if (doc != nullptr) {
doc->RunAnalysis();
UpdateHint hint(HintType::kWeathercasesEdit);
doc->UpdateAllViews(nullptr, &hint);
}
}
}
void SpanAnalyzerFrame::OnMenuFilePreferences(wxCommandEvent& event) {
// gets the application config
SpanAnalyzerConfig* config = wxGetApp().config();
// stores a copy of the unit system before letting user edit
units::UnitSystem units_before = config->units;
// creates preferences editor dialog and shows
// exits if user closes/cancels
PreferencesDialog preferences(this, config);
if (preferences.ShowModal() != wxID_OK) {
return;
}
wxBusyCursor cursor;
// application data change is implemented on app restart
// converts unit system if it changed
SpanAnalyzerData* data = wxGetApp().data();
if (units_before != config->units) {
// converts app data
for (auto iter = data->groups_weathercase.begin();
iter != data->groups_weathercase.end(); iter++) {
WeatherLoadCaseGroup& group = *iter;
for (auto it = group.weathercases.begin();
it != group.weathercases.end(); it++) {
WeatherLoadCase& weathercase = *it;
WeatherLoadCaseUnitConverter::ConvertUnitSystem(
units_before,
config->units,
weathercase);
}
}
for (auto iter = data->cablefiles.begin(); iter != data->cablefiles.end();
iter++) {
CableFile* cablefile = *iter;
CableUnitConverter::ConvertUnitSystem(
units_before,
config->units,
cablefile->cable);
}
// updates document/views
SpanAnalyzerDoc* doc = (SpanAnalyzerDoc*)wxGetApp().manager_doc()->
GetCurrentDocument();
if (doc != nullptr) {
doc->ConvertUnitSystem(units_before, config->units);
doc->RunAnalysis();
// updates views
UpdateHint hint(HintType::kPreferencesEdit);
doc->UpdateAllViews(nullptr, &hint);
}
}
// updates logging level
wxLog::SetLogLevel(config->level_log);
}
void SpanAnalyzerFrame::OnMenuHelpAbout(wxCommandEvent& event) {
// sets the dialog info
wxAboutDialogInfo info;
info.SetIcon(wxICON(icon));
info.SetName(wxGetApp().GetAppDisplayName());
info.SetVersion("0.1");
info.SetCopyright("License: http://unlicense.org/");
info.SetDescription(
"This application provides a GUI for calculating the sag-tension response\n"
"of transmission line cables.\n"
"\n"
"This application is part of the Overhead Transmission Line Software\n"
"suite. For the actual engineering modeling and sag-tension computations,\n"
"see the Models library.\n"
"\n"
"This software was developed so that transmission engineers can know\n"
"exactly how results are calculated, and so that the software can be\n"
"freely modified to fit the unique needs of the utility they represent.\n"
"\n"
"To get involved in project development, or to review the code, see the\n"
"website link.");
info.SetWebSite("https://github.com/OverheadTransmissionLineSoftware/SpanAnalyzer");
// shows the dialog
wxAboutBox(info, this);
}
void SpanAnalyzerFrame::OnMenuViewLog(wxCommandEvent& event) {
wxAuiPaneInfo& info = manager_.GetPane("Log");
if (info.IsShown() == false) {
info.Show(true);
} else {
info.Show(false);
}
manager_.Update();
}
LogPane* SpanAnalyzerFrame::pane_log() {
return pane_log_;
}
<commit_msg>Removed cable file flushing.<commit_after>// This is free and unencumbered software released into the public domain.
// For more information, please refer to <http://unlicense.org/>
#include "span_analyzer_frame.h"
#include "wx/aboutdlg.h"
#include "wx/xrc/xmlres.h"
#include "cable_file_manager_dialog.h"
#include "cable_unit_converter.h"
#include "file_handler.h"
#include "preferences_dialog.h"
#include "span_analyzer_app.h"
#include "span_analyzer_doc.h"
#include "span_analyzer_view.h"
#include "weather_load_case_manager_dialog.h"
#include "weather_load_case_unit_converter.h"
#include "../res/icon.xpm"
DocumentFileDropTarget::DocumentFileDropTarget(wxWindow* parent) {
parent_ = parent;
// creates data object to store dropped information
SetDataObject(new wxFileDataObject());
SetDefaultAction(wxDragCopy);
}
bool DocumentFileDropTarget::OnDropFiles(wxCoord x, wxCoord y,
const wxArrayString& filenames) {
// gets data from drag-and-drop operation
wxFileDataObject* data = (wxFileDataObject*)GetDataObject();
// tests if file exists
// only the first file in the list is processed
const wxString& str_file = data->GetFilenames().front();
if (wxFileName::Exists(str_file) == false) {
return false;
}
// tests if extension matches application document
wxFileName path(str_file);
if (path.GetExt() == ".spananalyzer") {
return false;
}
// freezes frame, opens document, and thaws frame
parent_->Freeze();
wxGetApp().manager_doc()->CreateDocument(str_file);
parent_->Thaw();
return true;
}
BEGIN_EVENT_TABLE(SpanAnalyzerFrame, wxFrame)
EVT_MENU(XRCID("menuitem_edit_cables"), SpanAnalyzerFrame::OnMenuEditCables)
EVT_MENU(XRCID("menuitem_edit_weathercases"), SpanAnalyzerFrame::OnMenuEditWeathercases)
EVT_MENU(XRCID("menuitem_file_preferences"), SpanAnalyzerFrame::OnMenuFilePreferences)
EVT_MENU(XRCID("menuitem_help_about"), SpanAnalyzerFrame::OnMenuHelpAbout)
EVT_MENU(XRCID("menuitem_view_log"), SpanAnalyzerFrame::OnMenuViewLog)
END_EVENT_TABLE()
SpanAnalyzerFrame::SpanAnalyzerFrame(wxDocManager* manager)
: wxDocParentFrame(manager, nullptr, wxID_ANY, "Span Analyzer") {
// loads dialog from virtual xrc file system
wxXmlResource::Get()->LoadMenuBar(this, "span_analyzer_menubar");
// sets the frame icon
SetIcon(wxIcon(icon_xpm));
// sets the drag and drop target
SetDropTarget(new DocumentFileDropTarget(this));
// tells aui manager to manage this frame
manager_.SetManagedWindow(this);
// creates log AUI window and adds to manager
wxAuiPaneInfo info;
info.Name("Log");
info.Float();
info.Caption("Log");
info.CloseButton(true);
info.Show(false);
pane_log_ = new LogPane(this);
manager_.AddPane(pane_log_, info);
manager_.Update();
}
SpanAnalyzerFrame::~SpanAnalyzerFrame() {
// saves frame size to application config
SpanAnalyzerConfig* config = wxGetApp().config();
if (this->IsMaximized() == true) {
config->size_frame = wxSize(0, 0);
} else {
config->size_frame = this->GetSize();
}
manager_.UnInit();
}
void SpanAnalyzerFrame::OnMenuEditCables(wxCommandEvent& event) {
// gets application config and data
const SpanAnalyzerConfig* config = wxGetApp().config();
SpanAnalyzerData* data = wxGetApp().data();
// creates and shows the cable file manager dialog
CableFileManagerDialog dialog(this, config->units, &data->cablefiles);
if (dialog.ShowModal() == wxID_OK) {
wxBusyCursor cursor;
// saves application data
FileHandler::SaveAppData(config->filepath_data, *data, config->units);
}
wxBusyCursor cursor;
// updates document/views
SpanAnalyzerDoc* doc = (SpanAnalyzerDoc*)wxGetApp().manager_doc()->
GetCurrentDocument();
if (doc != nullptr) {
doc->RunAnalysis();
UpdateHint hint(HintType::kCablesEdit);
doc->UpdateAllViews(nullptr, &hint);
}
}
void SpanAnalyzerFrame::OnMenuEditWeathercases(
wxCommandEvent& event) {
// gets application data
SpanAnalyzerData* data = wxGetApp().data();
// shows an editor
WeatherLoadCaseManagerDialog dialog(
this,
wxGetApp().config()->units,
&data->groups_weathercase);
if (dialog.ShowModal() == wxID_OK) {
wxBusyCursor cursor;
// saves application data
FileHandler::SaveAppData(wxGetApp().config()->filepath_data, *data,
wxGetApp().config()->units);
// updates document/views
SpanAnalyzerDoc* doc = (SpanAnalyzerDoc*)wxGetApp().manager_doc()->
GetCurrentDocument();
if (doc != nullptr) {
doc->RunAnalysis();
UpdateHint hint(HintType::kWeathercasesEdit);
doc->UpdateAllViews(nullptr, &hint);
}
}
}
void SpanAnalyzerFrame::OnMenuFilePreferences(wxCommandEvent& event) {
// gets the application config
SpanAnalyzerConfig* config = wxGetApp().config();
// stores a copy of the unit system before letting user edit
units::UnitSystem units_before = config->units;
// creates preferences editor dialog and shows
// exits if user closes/cancels
PreferencesDialog preferences(this, config);
if (preferences.ShowModal() != wxID_OK) {
return;
}
wxBusyCursor cursor;
// application data change is implemented on app restart
// converts unit system if it changed
SpanAnalyzerData* data = wxGetApp().data();
if (units_before != config->units) {
// converts app data
for (auto iter = data->groups_weathercase.begin();
iter != data->groups_weathercase.end(); iter++) {
WeatherLoadCaseGroup& group = *iter;
for (auto it = group.weathercases.begin();
it != group.weathercases.end(); it++) {
WeatherLoadCase& weathercase = *it;
WeatherLoadCaseUnitConverter::ConvertUnitSystem(
units_before,
config->units,
weathercase);
}
}
for (auto iter = data->cablefiles.begin(); iter != data->cablefiles.end();
iter++) {
CableFile* cablefile = *iter;
CableUnitConverter::ConvertUnitSystem(
units_before,
config->units,
cablefile->cable);
}
// updates document/views
SpanAnalyzerDoc* doc = (SpanAnalyzerDoc*)wxGetApp().manager_doc()->
GetCurrentDocument();
if (doc != nullptr) {
doc->ConvertUnitSystem(units_before, config->units);
doc->RunAnalysis();
// updates views
UpdateHint hint(HintType::kPreferencesEdit);
doc->UpdateAllViews(nullptr, &hint);
}
}
// updates logging level
wxLog::SetLogLevel(config->level_log);
}
void SpanAnalyzerFrame::OnMenuHelpAbout(wxCommandEvent& event) {
// sets the dialog info
wxAboutDialogInfo info;
info.SetIcon(wxICON(icon));
info.SetName(wxGetApp().GetAppDisplayName());
info.SetVersion("0.1");
info.SetCopyright("License: http://unlicense.org/");
info.SetDescription(
"This application provides a GUI for calculating the sag-tension response\n"
"of transmission line cables.\n"
"\n"
"This application is part of the Overhead Transmission Line Software\n"
"suite. For the actual engineering modeling and sag-tension computations,\n"
"see the Models library.\n"
"\n"
"This software was developed so that transmission engineers can know\n"
"exactly how results are calculated, and so that the software can be\n"
"freely modified to fit the unique needs of the utility they represent.\n"
"\n"
"To get involved in project development, or to review the code, see the\n"
"website link.");
info.SetWebSite("https://github.com/OverheadTransmissionLineSoftware/SpanAnalyzer");
// shows the dialog
wxAboutBox(info, this);
}
void SpanAnalyzerFrame::OnMenuViewLog(wxCommandEvent& event) {
wxAuiPaneInfo& info = manager_.GetPane("Log");
if (info.IsShown() == false) {
info.Show(true);
} else {
info.Show(false);
}
manager_.Update();
}
LogPane* SpanAnalyzerFrame::pane_log() {
return pane_log_;
}
<|endoftext|> |
<commit_before>#ifdef HAVE_CVS_IDENT
#ident "$Id: vvp_vpi.cc,v 1.7 2003/01/09 04:09:44 steve Exp $"
#endif
#include <stdarg.h>
#include "vpi_user.h"
#include "vpithunk.h"
vpi_thunk vvpt;
void vvp_vpi_init()
{
vvpt.magic = VPI_THUNK_MAGIC;
vvpt.vpi_register_systf = vpi_register_systf;
vvpt.vpi_vprintf = vpi_vprintf;
vvpt.vpi_mcd_close = vpi_mcd_close;
vvpt.vpi_mcd_name = vpi_mcd_name;
vvpt.vpi_mcd_open = vpi_mcd_open;
vvpt.vpi_mcd_open_x = vpi_mcd_open_x;
vvpt.vpi_mcd_vprintf = vpi_mcd_vprintf;
vvpt.vpi_mcd_fputc = vpi_mcd_fputc;
vvpt.vpi_mcd_fgetc = vpi_mcd_fgetc;
vvpt.vpi_register_cb = vpi_register_cb;
vvpt.vpi_remove_cb = vpi_remove_cb;
vvpt.vpi_sim_vcontrol = vpi_sim_vcontrol;
vvpt.vpi_handle = vpi_handle;
vvpt.vpi_iterate = vpi_iterate;
vvpt.vpi_scan = vpi_scan;
vvpt.vpi_handle_by_index = vpi_handle_by_index;
vvpt.vpi_handle_by_name = vpi_handle_by_name;
vvpt.vpi_get_time = vpi_get_time;
vvpt.vpi_get = vpi_get;
vvpt.vpi_get_str = vpi_get_str;
vvpt.vpi_get_value = vpi_get_value;
vvpt.vpi_put_value = vpi_put_value;
vvpt.vpi_free_object= vpi_free_object;
vvpt.vpi_get_vlog_info = vpi_get_vlog_info;
vvpt.vpi_chk_error = vpi_chk_error;
vvpt.vpi_get_userdata = vpi_get_userdata;
vvpt.vpi_put_userdata = vpi_put_userdata;
}
/*
* $Log: vvp_vpi.cc,v $
* Revision 1.7 2003/01/09 04:09:44 steve
* Add vpi_put_userdata
*
* Revision 1.6 2002/12/11 23:55:22 steve
* Add vpi_handle_by_name to the VPI interface,
* and bump the vpithunk magic number.
*
* Revision 1.5 2002/08/12 01:35:09 steve
* conditional ident string using autoconfig.
*
* Revision 1.4 2002/08/11 23:47:05 steve
* Add missing Log and Ident strings.
*
*/
<commit_msg> Remove thunks from vpi init.<commit_after>#ifdef HAVE_CVS_IDENT
#ident "$Id: vvp_vpi.cc,v 1.8 2003/01/10 19:01:38 steve Exp $"
#endif
#include <stdarg.h>
#include "vpi_user.h"
void vvp_vpi_init()
{
}
/*
* $Log: vvp_vpi.cc,v $
* Revision 1.8 2003/01/10 19:01:38 steve
* Remove thunks from vpi init.
*
*/
<|endoftext|> |
<commit_before>/*
* Copyright (c) 2008-2016 the MRtrix3 contributors
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/
*
* MRtrix is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* For more details, see www.mrtrix.org
*
*/
#include <fstream>
#include <vector>
#include "file/json_utils.h"
#include "file/nifti_utils.h"
#include "exception.h"
#include "header.h"
#include "mrtrix.h"
#include "phase_encoding.h"
#include "file/ofstream.h"
namespace MR
{
namespace File
{
namespace JSON
{
void load (Header& H, const std::string& path)
{
std::ifstream in (path);
if (!in)
throw Exception ("Error opening JSON file \"" + path + "\"");
nlohmann::json json;
try {
in >> json;
} catch (std::logic_error& e) {
throw Exception ("Error parsing JSON file \"" + path + "\": " + e.what());
}
for (auto i = json.cbegin(); i != json.cend(); ++i) {
if (i->is_boolean()) {
H.keyval().insert (std::make_pair (i.key(), i.value() ? "1" : "0"));
} else if (i->is_number_integer()) {
H.keyval().insert (std::make_pair (i.key(), str<int>(i.value())));
} else if (i->is_number_float()) {
H.keyval().insert (std::make_pair (i.key(), str<float>(i.value())));
} else if (i->is_array()) {
std::vector<std::string> s;
for (auto j = i->cbegin(); j != i->cend(); ++j)
s.push_back (str(*j));
H.keyval().insert (std::make_pair (i.key(), join(s, "\n")));
} else if (i->is_string()) {
const std::string s = i.value();
H.keyval().insert (std::make_pair (i.key(), s));
}
}
}
void save (const Header& H, const std::string& path)
{
nlohmann::json json;
auto pe_scheme = PhaseEncoding::get_scheme (H);
std::vector<size_t> order;
File::NIfTI::adjust_transform (H, order);
if (pe_scheme.rows() && (order[0] != 0 || order[1] != 1 || order[2] != 2 || H.stride(0) < 0 || H.stride(1) < 0 || H.stride(2) < 0)) {
// Assume that image being written to disk is going to have its transform adjusted,
// so modify the phase encoding scheme appropriately before writing to JSON
for (ssize_t row = 0; row != pe_scheme.rows(); ++row) {
auto new_line = pe_scheme.row (row);
for (ssize_t axis = 0; axis != 3; ++axis)
new_line[axis] = H.stride (order[axis]) > 0 ? pe_scheme(row, order[axis]) : -pe_scheme(row, order[axis]);
pe_scheme.row (row) = new_line;
}
Header H_adj (H);
PhaseEncoding::set_scheme (H_adj, pe_scheme);
for (const auto& kv : H_adj.keyval())
json[kv.first] = kv.second;
INFO ("Phase encoding information written to JSON file modified according to expected header transform realignment");
} else {
// Straight copy
for (const auto& kv : H.keyval())
json[kv.first] = kv.second;
}
File::OFStream out (path);
out << json.dump(4);
}
}
}
}
<commit_msg>JSON import: Rotate phase encoding scheme<commit_after>/*
* Copyright (c) 2008-2016 the MRtrix3 contributors
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/
*
* MRtrix is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* For more details, see www.mrtrix.org
*
*/
#include <fstream>
#include <vector>
#include "file/json_utils.h"
#include "file/nifti_utils.h"
#include "exception.h"
#include "header.h"
#include "mrtrix.h"
#include "phase_encoding.h"
#include "file/ofstream.h"
namespace MR
{
namespace File
{
namespace JSON
{
void load (Header& H, const std::string& path)
{
std::ifstream in (path);
if (!in)
throw Exception ("Error opening JSON file \"" + path + "\"");
nlohmann::json json;
try {
in >> json;
} catch (std::logic_error& e) {
throw Exception ("Error parsing JSON file \"" + path + "\": " + e.what());
}
for (auto i = json.cbegin(); i != json.cend(); ++i) {
if (i->is_boolean()) {
H.keyval().insert (std::make_pair (i.key(), i.value() ? "1" : "0"));
} else if (i->is_number_integer()) {
H.keyval().insert (std::make_pair (i.key(), str<int>(i.value())));
} else if (i->is_number_float()) {
H.keyval().insert (std::make_pair (i.key(), str<float>(i.value())));
} else if (i->is_array()) {
std::vector<std::string> s;
for (auto j = i->cbegin(); j != i->cend(); ++j)
s.push_back (str(*j));
H.keyval().insert (std::make_pair (i.key(), join(s, "\n")));
} else if (i->is_string()) {
const std::string s = i.value();
H.keyval().insert (std::make_pair (i.key(), s));
}
}
auto pe_scheme = PhaseEncoding::get_scheme (H);
std::vector<size_t> order;
File::NIfTI::adjust_transform (H, order);
if (pe_scheme.rows() && (order[0] != 0 || order[1] != 1 || order[2] != 2 || H.stride(0) < 0 || H.stride(1) < 0 || H.stride(2) < 0)) {
// The corresponding header may have been rotated on image load prior to the JSON
// being loaded. If this is the case, the phase encoding scheme will need to be
// correspondingly rotated on import.
for (ssize_t row = 0; row != pe_scheme.rows(); ++row) {
auto new_line = pe_scheme.row (row);
for (ssize_t axis = 0; axis != 3; ++axis)
new_line[order[axis]] = H.stride (order[axis]) > 0 ? pe_scheme(row,axis) : -pe_scheme(row,axis);
pe_scheme.row (row) = new_line;
}
PhaseEncoding::set_scheme (H, pe_scheme);
INFO ("Phase encoding information read from JSON file modified according to expected header transform realignment");
}
}
void save (const Header& H, const std::string& path)
{
nlohmann::json json;
auto pe_scheme = PhaseEncoding::get_scheme (H);
std::vector<size_t> order;
File::NIfTI::adjust_transform (H, order);
if (pe_scheme.rows() && (order[0] != 0 || order[1] != 1 || order[2] != 2 || H.stride(0) < 0 || H.stride(1) < 0 || H.stride(2) < 0)) {
// Assume that image being written to disk is going to have its transform adjusted,
// so modify the phase encoding scheme appropriately before writing to JSON
for (ssize_t row = 0; row != pe_scheme.rows(); ++row) {
auto new_line = pe_scheme.row (row);
for (ssize_t axis = 0; axis != 3; ++axis)
new_line[axis] = H.stride (order[axis]) > 0 ? pe_scheme(row, order[axis]) : -pe_scheme(row, order[axis]);
pe_scheme.row (row) = new_line;
}
Header H_adj (H);
PhaseEncoding::set_scheme (H_adj, pe_scheme);
for (const auto& kv : H_adj.keyval())
json[kv.first] = kv.second;
INFO ("Phase encoding information written to JSON file modified according to expected header transform realignment");
} else {
// Straight copy
for (const auto& kv : H.keyval())
json[kv.first] = kv.second;
}
File::OFStream out (path);
out << json.dump(4);
}
}
}
}
<|endoftext|> |
<commit_before>#pragma once
#include <boost/preprocessor/seq/for_each.hpp>
#include "all_type_variant.hpp"
#include "storage/base_value_column.hpp"
#include "storage/chunk.hpp"
#include "storage/column_iterables/base_column_iterators.hpp"
namespace opossum {
// We need a boolean data type in the JitOperator, but don't want to add it to
// DATA_TYPE_INFO to avoid costly template instantiations.
// See "all_type_variant.hpp" for details.
#define JIT_DATA_TYPE_INFO ((bool, Bool, "bool")) DATA_TYPE_INFO
#define JIT_VARIANT_VECTOR_MEMBER(r, d, type) \
std::vector<BOOST_PP_TUPLE_ELEM(3, 0, type)> BOOST_PP_TUPLE_ELEM(3, 1, type);
#define JIT_VARIANT_VECTOR_RESIZE(r, d, type) BOOST_PP_TUPLE_ELEM(3, 1, type).resize(new_size);
/* A brief overview of the type system and the way values are handled in the JitOperator:
*
* The JitOperator performs most of its operations on variant values, since this allows writing generic operators with
* an unlimited number of variably-typed operands (without the need for excessive templating).
* While this sounds costly at first, the jit engine knows the actual type of each value in advance and replaces generic
* operations with specialized versions for the concrete data types.
*
* This entails two important restrictions:
* 1) There can be no temporary (=local) variant values. This is because we support std::string as a data type.
* Strings are not POD types and they thus require memory allocations, destructors and exception
* handling. The specialization engine is not able to completely optimize this overhead away, even if no strings are
* processed in an operation.
* 2) The data type of each value needs to be stored separately from the value itself. This is because we want the
* specialization engine to know about data type, but not concrete values.
*
* Both restrictions are enforced using the same mechanism:
* All values (and other data that must not be available to the specialization engine) are encapsulated in the
* JitRuntimeContext. This context is only passed to the operator after code specialization has taken place.
* The JitRuntimeContext contains a vector of variant values (called tuple) which the JitOperator can access through
* JitTupleValue instances.
* The runtime tuple is created and destroyed outside the JitOperator's scope, so no memory management is
* required from within the operator.
* Each JitTupleValue encapsulates information about how to access a single value in the runtime tuple. However, the
* JitTupleValues are part of the JitOperator and must thus not store a reference to the JitRuntimeContext. So while
* they "know" how to access values in the runtime tuple, they do not have the means to do so.
* Only by passing the runtime context to a JitTupleValue, a JitMaterializedValue is created.
* This materialized value finally allows the operator to access a data value.
*/
/* The JitVariantVector can be used in two ways:
* 1) As a vector of variant values.
* Imagine you want to store a database row (aka tuple) of some table. Since each column of the table could have a
* different type, a std::vector<Variant> seems like a good choice. To store N values, the vector is resized to
* contain N slots and each value (representing one column) can be accessed by its index from [0, N).
* We do something slightly different here: Instead of one vector (where each vector element can hold any of a number
* of types), we create one strongly typed vector per data type. All of these vectors have size N, so each value
* (representing one column of the tuple) has a slot in each vector.
* Accessing the value at position P as an "int" will return the element at position P in the integer vector.
* There is no automatic type conversions happening here. Soring a value as "int" and reading it later as "double"
* won't work, since this accesses different memory locations in different vectors.
* This is not a problem, however, since the type of each value does not change throughout query execution.
*
* 2) As a variant vector.
* This data structure can also be used to store a vector of values of some unknown, but fixed type.
* Say you want to build an aggregate operator and need to store a column of aggregate values. All values
* produced will have the same type, but there is no way of knowing that type in advance.
* By adding a templated "push" function to the implementation below, we can add an arbitrary number of elements to
* the std::vector of that type. All other vectors will remain empty.
* This interpretation of the variant vector is not used in the code currently, but will be helpful when implementing
* further operators.
*/
class JitVariantVector {
public:
void resize(const size_t new_size) {
BOOST_PP_SEQ_FOR_EACH(JIT_VARIANT_VECTOR_RESIZE, _, JIT_DATA_TYPE_INFO)
_is_null.resize(new_size);
}
template <typename T>
T get(const size_t index) const;
template <typename T>
void set(const size_t index, const T value);
bool is_null(const size_t index) { return _is_null[index]; }
void set_is_null(const size_t index, const bool is_null) { _is_null[index] = is_null; }
private:
BOOST_PP_SEQ_FOR_EACH(JIT_VARIANT_VECTOR_MEMBER, _, JIT_DATA_TYPE_INFO)
std::vector<uint8_t> _is_null;
};
// The structure encapsulates all data available to the JitOperator at runtime,
// but NOT during code specialization.
struct JitRuntimeContext {
uint32_t chunk_size;
ChunkOffset chunk_offset;
JitVariantVector tuple;
std::vector<std::shared_ptr<JitBaseColumnIterator>> inputs;
std::vector<std::shared_ptr<BaseValueColumn>> outputs;
std::shared_ptr<Chunk> out_chunk;
};
struct JitMaterializedValue {
JitMaterializedValue(const DataType data_type, const bool is_nullable, const size_t vector_index,
JitVariantVector& vector)
: _data_type{data_type}, _is_nullable{is_nullable}, _vector_index{vector_index}, _vector{vector} {}
DataType data_type() const { return _data_type; }
bool is_nullable() const { return _is_nullable; }
template <typename T>
const T get() const {
return _vector.get<T>(_vector_index);
}
template <typename T>
void set(const T value) {
_vector.set<T>(_vector_index, value);
}
bool is_null() const { return _is_nullable && _vector.is_null(_vector_index); }
void set_is_null(const bool is_null) const { _vector.set_is_null(_vector_index, is_null); }
private:
const DataType _data_type;
const bool _is_nullable;
const size_t _vector_index;
JitVariantVector& _vector;
};
class JitTupleValue {
public:
JitTupleValue(const DataType data_type, const bool is_nullable, const size_t tuple_index)
: _data_type{data_type}, _is_nullable{is_nullable}, _tuple_index{tuple_index} {}
JitTupleValue(const std::pair<const DataType, const bool> data_type, const size_t tuple_index)
: _data_type{data_type.first}, _is_nullable{data_type.second}, _tuple_index{tuple_index} {}
DataType data_type() const { return _data_type; }
bool is_nullable() const { return _is_nullable; }
size_t tuple_index() const { return _tuple_index; }
// Converts this abstract value into an actually accessible value
JitMaterializedValue materialize(JitRuntimeContext& ctx) const {
return JitMaterializedValue(_data_type, _is_nullable, _tuple_index, ctx.tuple);
}
private:
const DataType _data_type;
const bool _is_nullable;
const size_t _tuple_index;
};
// cleanup
#undef JIT_VARIANT_VECTOR_MEMBER
#undef JIT_VARIANT_VECTOR_RESIZE
} // namespace opossum
<commit_msg>JIT: PR feedback 2.1 (#738)<commit_after>#pragma once
#include <boost/preprocessor/seq/for_each.hpp>
#include "all_type_variant.hpp"
#include "storage/base_value_column.hpp"
#include "storage/chunk.hpp"
#include "storage/column_iterables/base_column_iterators.hpp"
namespace opossum {
// We need a boolean data type in the JitOperator, but don't want to add it to
// DATA_TYPE_INFO to avoid costly template instantiations.
// See "all_type_variant.hpp" for details.
#define JIT_DATA_TYPE_INFO ((bool, Bool, "bool")) DATA_TYPE_INFO
#define JIT_VARIANT_VECTOR_MEMBER(r, d, type) \
std::vector<BOOST_PP_TUPLE_ELEM(3, 0, type)> BOOST_PP_TUPLE_ELEM(3, 1, type);
#define JIT_VARIANT_VECTOR_RESIZE(r, d, type) BOOST_PP_TUPLE_ELEM(3, 1, type).resize(new_size);
/* A brief overview of the type system and the way values are handled in the JitOperator:
*
* The JitOperator performs most of its operations on variant values, since this allows writing generic operators with
* an unlimited number of variably-typed operands (without the need for excessive templating).
* While this sounds costly at first, the jit engine knows the actual type of each value in advance and replaces generic
* operations with specialized versions for the concrete data types.
*
* This entails two important restrictions:
* 1) There can be no temporary (=local) variant values. This is because we support std::string as a data type.
* Strings are not POD types and they thus require memory allocations, destructors and exception
* handling. The specialization engine is not able to completely optimize this overhead away, even if no strings are
* processed in an operation.
* 2) The data type of each value needs to be stored separately from the value itself. This is because we want the
* specialization engine to know about data type, but not concrete values.
*
* Both restrictions are enforced using the same mechanism:
* All values (and other data that must not be available to the specialization engine) are encapsulated in the
* JitRuntimeContext. This context is only passed to the operator after code specialization has taken place.
* The JitRuntimeContext contains a vector of variant values (called tuple) which the JitOperator can access through
* JitTupleValue instances.
* The runtime tuple is created and destroyed outside the JitOperator's scope, so no memory management is
* required from within the operator.
* Each JitTupleValue encapsulates information about how to access a single value in the runtime tuple. However, the
* JitTupleValues are part of the JitOperator and must thus not store a reference to the JitRuntimeContext. So while
* they "know" how to access values in the runtime tuple, they do not have the means to do so.
* Only by passing the runtime context to a JitTupleValue, a JitMaterializedValue is created.
* This materialized value contains a reference to the underlying vector and finally allows the operator to access a
* data value.
*/
/* The JitVariantVector can be used in two ways:
* 1) As a vector of variant values.
* Imagine you want to store a database row (aka tuple) of some table. Since each column of the table could have a
* different type, a std::vector<Variant> seems like a good choice. To store N values, the vector is resized to
* contain N slots and each value (representing one column) can be accessed by its index from [0, N).
* We do something slightly different here: Instead of one vector (where each vector element can hold any of a number
* of types), we create one strongly typed vector per data type. All of these vectors have size N, so each value
* (representing one column of the tuple) has a slot in each vector.
* Accessing the value at position P as an "int" will return the element at position P in the integer vector.
* There is no automatic type conversions happening here. Storing a value as "int" and reading it later as "double"
* won't work, since this accesses different memory locations in different vectors.
* This is not a problem, however, since the type of each value does not change throughout query execution.
*
* 2) As a variant vector.
* This data structure can also be used to store a vector of values of some unknown, but fixed type.
* Say you want to build an aggregate operator and need to store a column of aggregate values. All values
* produced will have the same type, but there is no way of knowing that type in advance.
* By adding a templated "push" function to the implementation below, we can add an arbitrary number of elements to
* the std::vector of that type. All other vectors will remain empty.
* This interpretation of the variant vector is not used in the code currently, but will be helpful when implementing
* further operators.
*/
class JitVariantVector {
public:
void resize(const size_t new_size) {
BOOST_PP_SEQ_FOR_EACH(JIT_VARIANT_VECTOR_RESIZE, _, JIT_DATA_TYPE_INFO)
_is_null.resize(new_size);
}
template <typename T>
T get(const size_t index) const;
template <typename T>
void set(const size_t index, const T value);
bool is_null(const size_t index) { return _is_null[index]; }
void set_is_null(const size_t index, const bool is_null) { _is_null[index] = is_null; }
private:
BOOST_PP_SEQ_FOR_EACH(JIT_VARIANT_VECTOR_MEMBER, _, JIT_DATA_TYPE_INFO)
std::vector<uint8_t> _is_null;
};
// The structure encapsulates all data available to the JitOperator at runtime,
// but NOT during code specialization.
struct JitRuntimeContext {
uint32_t chunk_size;
ChunkOffset chunk_offset;
JitVariantVector tuple;
std::vector<std::shared_ptr<JitBaseColumnIterator>> inputs;
std::vector<std::shared_ptr<BaseValueColumn>> outputs;
std::shared_ptr<Chunk> out_chunk;
};
// A JitMaterializedValue is a wrapper to access an actual value in the runtime context.
// While a JitTupleValue is only an abstract representation of the value (knowing how to access it, but not being able
// to actually do so), the JitMaterializedValue can access the value.
// It is usually created from a JitTupleValue by providing the context at runtime.
struct JitMaterializedValue {
JitMaterializedValue(const DataType data_type, const bool is_nullable, const size_t vector_index,
JitVariantVector& vector)
: _data_type{data_type}, _is_nullable{is_nullable}, _vector_index{vector_index}, _vector{vector} {}
DataType data_type() const { return _data_type; }
bool is_nullable() const { return _is_nullable; }
template <typename T>
const T get() const {
return _vector.get<T>(_vector_index);
}
template <typename T>
void set(const T value) {
_vector.set<T>(_vector_index, value);
}
bool is_null() const { return _is_nullable && _vector.is_null(_vector_index); }
void set_is_null(const bool is_null) const { _vector.set_is_null(_vector_index, is_null); }
private:
const DataType _data_type;
const bool _is_nullable;
const size_t _vector_index;
JitVariantVector& _vector;
};
// The JitTupleValue represents a value in the runtime tuple.
// The JitTupleValue has information about the DataType and index of the value it represents, but it does NOT have
// a reference to the runtime tuple with the actual values.
// however, this is enough for the jit engine to optimize any operation involving the value.
// It only knows how to access the value, once it gets converted to a JitMaterializedValue by providing the runtime
// context.
class JitTupleValue {
public:
JitTupleValue(const DataType data_type, const bool is_nullable, const size_t tuple_index)
: _data_type{data_type}, _is_nullable{is_nullable}, _tuple_index{tuple_index} {}
JitTupleValue(const std::pair<const DataType, const bool> data_type, const size_t tuple_index)
: _data_type{data_type.first}, _is_nullable{data_type.second}, _tuple_index{tuple_index} {}
DataType data_type() const { return _data_type; }
bool is_nullable() const { return _is_nullable; }
size_t tuple_index() const { return _tuple_index; }
// Converts this abstract value into an actually accessible value
JitMaterializedValue materialize(JitRuntimeContext& ctx) const {
return JitMaterializedValue(_data_type, _is_nullable, _tuple_index, ctx.tuple);
}
private:
const DataType _data_type;
const bool _is_nullable;
const size_t _tuple_index;
};
// cleanup
#undef JIT_VARIANT_VECTOR_MEMBER
#undef JIT_VARIANT_VECTOR_RESIZE
} // namespace opossum
<|endoftext|> |
<commit_before>#include "ipuptanesecondary.h"
#include "asn1/asn1_message.h"
#include "der_encoder.h"
#include "logging/logging.h"
#include <memory>
namespace Uptane {
PublicKey IpUptaneSecondary::getPublicKey() {
LOG_INFO << "Getting the public key of a secondary";
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_publicKeyReq);
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_publicKeyResp) {
LOG_ERROR << "Failed to get public key response message from secondary";
return PublicKey("", KeyType::kUnknown);
}
auto r = resp->publicKeyResp();
std::string key = ToString(r->key);
auto type = static_cast<KeyType>(r->type);
return PublicKey(key, type);
}
bool IpUptaneSecondary::putMetadata(const RawMetaPack& meta_pack) {
LOG_INFO << "Sending Uptane metadata to the secondary";
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_putMetaReq);
auto m = req->putMetaReq();
m->image.present = image_PR_json;
SetString(&m->image.choice.json.root, meta_pack.image_root); // NOLINT
SetString(&m->image.choice.json.targets, meta_pack.image_targets); // NOLINT
SetString(&m->image.choice.json.snapshot, meta_pack.image_snapshot); // NOLINT
SetString(&m->image.choice.json.timestamp, meta_pack.image_timestamp); // NOLINT
m->director.present = director_PR_json;
SetString(&m->director.choice.json.root, meta_pack.director_root); // NOLINT
SetString(&m->director.choice.json.targets, meta_pack.director_targets); // NOLINT
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_putMetaResp) {
LOG_ERROR << "Failed to get response to sending manifest to secondary";
return false;
}
auto r = resp->putMetaResp();
return r->result == AKInstallationResult_success;
}
bool IpUptaneSecondary::sendFirmwareAsync(const std::shared_ptr<std::string>& data) {
if (!install_future.valid() || install_future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) {
install_future = std::async(std::launch::async, &IpUptaneSecondary::sendFirmware, this, std::ref(data));
return true;
}
return false;
}
bool IpUptaneSecondary::sendFirmware(const std::shared_ptr<std::string>& data) {
LOG_INFO << "Sending firmware to the secondary";
sendEvent(std::make_shared<event::InstallStarted>(getSerial()));
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_sendFirmwareReq);
auto m = req->sendFirmwareReq();
SetString(&m->firmware, *data);
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_sendFirmwareResp) {
LOG_ERROR << "Failed to get response to sending firmware to secondary";
sendEvent(std::make_shared<event::InstallComplete>(getSerial()));
return false;
}
auto r = resp->sendFirmwareResp();
sendEvent(std::make_shared<event::InstallComplete>(getSerial()));
return r->result == AKInstallationResult_success;
}
Json::Value IpUptaneSecondary::getManifest() {
LOG_INFO << "Getting the manifest key of a secondary";
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_manifestReq);
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_manifestResp) {
LOG_ERROR << "Failed to get public key response message from secondary";
return Json::Value();
}
auto r = resp->manifestResp();
if (r->manifest.present != manifest_PR_json) {
LOG_ERROR << "Manifest wasn't in json format";
return Json::Value();
}
std::string manifest = ToString(r->manifest.choice.json); // NOLINT
return Utils::parseJSON(manifest);
}
} // namespace Uptane
<commit_msg>Fix a remaining async lifetime issue<commit_after>#include "ipuptanesecondary.h"
#include "asn1/asn1_message.h"
#include "der_encoder.h"
#include "logging/logging.h"
#include <memory>
namespace Uptane {
PublicKey IpUptaneSecondary::getPublicKey() {
LOG_INFO << "Getting the public key of a secondary";
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_publicKeyReq);
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_publicKeyResp) {
LOG_ERROR << "Failed to get public key response message from secondary";
return PublicKey("", KeyType::kUnknown);
}
auto r = resp->publicKeyResp();
std::string key = ToString(r->key);
auto type = static_cast<KeyType>(r->type);
return PublicKey(key, type);
}
bool IpUptaneSecondary::putMetadata(const RawMetaPack& meta_pack) {
LOG_INFO << "Sending Uptane metadata to the secondary";
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_putMetaReq);
auto m = req->putMetaReq();
m->image.present = image_PR_json;
SetString(&m->image.choice.json.root, meta_pack.image_root); // NOLINT
SetString(&m->image.choice.json.targets, meta_pack.image_targets); // NOLINT
SetString(&m->image.choice.json.snapshot, meta_pack.image_snapshot); // NOLINT
SetString(&m->image.choice.json.timestamp, meta_pack.image_timestamp); // NOLINT
m->director.present = director_PR_json;
SetString(&m->director.choice.json.root, meta_pack.director_root); // NOLINT
SetString(&m->director.choice.json.targets, meta_pack.director_targets); // NOLINT
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_putMetaResp) {
LOG_ERROR << "Failed to get response to sending manifest to secondary";
return false;
}
auto r = resp->putMetaResp();
return r->result == AKInstallationResult_success;
}
bool IpUptaneSecondary::sendFirmwareAsync(const std::shared_ptr<std::string>& data) {
if (!install_future.valid() || install_future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) {
install_future = std::async(std::launch::async, &IpUptaneSecondary::sendFirmware, this, data);
return true;
}
return false;
}
bool IpUptaneSecondary::sendFirmware(const std::shared_ptr<std::string>& data) {
LOG_INFO << "Sending firmware to the secondary";
sendEvent(std::make_shared<event::InstallStarted>(getSerial()));
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_sendFirmwareReq);
auto m = req->sendFirmwareReq();
SetString(&m->firmware, *data);
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_sendFirmwareResp) {
LOG_ERROR << "Failed to get response to sending firmware to secondary";
sendEvent(std::make_shared<event::InstallComplete>(getSerial()));
return false;
}
auto r = resp->sendFirmwareResp();
sendEvent(std::make_shared<event::InstallComplete>(getSerial()));
return r->result == AKInstallationResult_success;
}
Json::Value IpUptaneSecondary::getManifest() {
LOG_INFO << "Getting the manifest key of a secondary";
Asn1Message::Ptr req(Asn1Message::Empty());
req->present(AKIpUptaneMes_PR_manifestReq);
auto resp = Asn1Rpc(req, getAddr());
if (resp->present() != AKIpUptaneMes_PR_manifestResp) {
LOG_ERROR << "Failed to get public key response message from secondary";
return Json::Value();
}
auto r = resp->manifestResp();
if (r->manifest.present != manifest_PR_json) {
LOG_ERROR << "Manifest wasn't in json format";
return Json::Value();
}
std::string manifest = ToString(r->manifest.choice.json); // NOLINT
return Utils::parseJSON(manifest);
}
} // namespace Uptane
<|endoftext|> |
<commit_before>#include <lug/Window/Android/WindowImplAndroid.hpp>
#include <mutex>
namespace lug {
namespace Window {
namespace priv {
std::mutex WindowImpl::androidMutex;
std::condition_variable WindowImpl::cv;
std::queue<lug::Window::Event> WindowImpl::events;
AInputQueue* WindowImpl::inputQueue = nullptr;
ANativeWindow* WindowImpl::nativeWindow = nullptr;
ANativeActivity* WindowImpl::activity = nullptr;
WindowImpl::WindowImpl(Window* win) : _parent{win} {}
bool WindowImpl::init(const Window::InitInfo&) {
if (!WindowImpl::nativeWindow) {
std::unique_lock<std::mutex> lk(WindowImpl::androidMutex);
WindowImpl::cv.wait(lk);
}
_parent->_mode.width = ANativeWindow_getWidth(nativeWindow);
_parent->_mode.height = ANativeWindow_getHeight(nativeWindow);
return true;
}
void WindowImpl::close() {}
ANativeWindow* WindowImpl::getWindow() {
return nativeWindow;
}
// credits to nvidia : https://github.com/NVIDIAGameWorks/GraphicsSamples/blob/master/extensions/src/NvGamepad/android/NvGamepadAndroid.cpp
float WindowImpl::MapCenteredAxis(AInputEvent* event, int32_t axis) {
const float deadZone = (8689.0f / 32768.0f); // 0,2651672363
float value = AMotionEvent_getAxisValue(event, axis, 0);
if (value > deadZone) {
return (value - deadZone) / (1.0f - deadZone);
} else if (value < -deadZone) {
return (value + deadZone) / (1.0f - deadZone);
} else {
return 0.0f;
}
}
int32_t WindowImpl::HandleInput(lug::Window::Event& event, AInputEvent* androidEvent) {
//TODO : refactor
// Engine* eng = (Engine*)app->userData;
event.touchScreen.drag = false;
event.touchScreen.tap = false;
event.touchScreen.pinch = false;
event.touchScreen.state = lug::Window::TouchScreenEvent::GestureState::None;
if (AInputEvent_getType(androidEvent) == AINPUT_EVENT_TYPE_MOTION) {
event.type = Event::Type::TouchScreenChange;
ndk_helper::GESTURE_STATE doubleTapState = doubletap_detector_.Detect(androidEvent);
ndk_helper::GESTURE_STATE dragState = drag_detector_.Detect(androidEvent);
ndk_helper::GESTURE_STATE pinchState = pinch_detector_.Detect(androidEvent);
// Double tap detector has a priority over other detectors
if (doubleTapState == ndk_helper::GESTURE_STATE_ACTION) {
event.touchScreen.doubleTap = !event.touchScreen.doubleTap;
event.touchScreen.state = static_cast<lug::Window::TouchScreenEvent::GestureState>(doubleTapState);
drag_detector_.GetPointer(event.touchScreen.coordinates[0]);
}
// Drag state
else if (dragState & ndk_helper::GESTURE_STATE_START ||
dragState & ndk_helper::GESTURE_STATE_MOVE ||
dragState & ndk_helper::GESTURE_STATE_END) {
event.touchScreen.drag = true;
event.touchScreen.state = static_cast<lug::Window::TouchScreenEvent::GestureState>(dragState);
drag_detector_.GetPointer(event.touchScreen.coordinates[0]);
}
// Pinch state
else if (pinchState & ndk_helper::GESTURE_STATE_START ||
pinchState & ndk_helper::GESTURE_STATE_MOVE ||
pinchState & ndk_helper::GESTURE_STATE_END) {
event.touchScreen.pinch = true;
event.touchScreen.state = static_cast<lug::Window::TouchScreenEvent::GestureState>(pinchState);
pinch_detector_.GetPointers(event.touchScreen.coordinates[0], event.touchScreen.coordinates[1]);
}
return 1;
}
return 0;
}
bool WindowImpl::pollEvent(lug::Window::Event& event) {
if (inputQueue != nullptr) {
AInputEvent* androidEvent = nullptr;
if (AInputQueue_getEvent(inputQueue, &androidEvent) >= 0) {
if (AInputQueue_preDispatchEvent(inputQueue, androidEvent)) {
return false;
}
HandleInput(event, androidEvent);
LUG_LOG.info("WINDOWS ANDROID event coordinate {} {}", event.touchScreen.coordinates[0].x(), event.touchScreen.coordinates[0].y());
events.push(std::move(event));
AInputQueue_finishEvent(inputQueue, androidEvent, 1);
}
}
if (!events.empty()) {
event = events.front();
events.pop();
return true;
}
return false;
}
void WindowImpl::setKeyRepeat(bool state) {
(void)state;
// TODO
}
void WindowImpl::setMouseCursorVisible(bool visible) {
(void)visible;
// TODO
}
void WindowImpl::setMousePos(const Math::Vec2i& mousePosition) {
(void)mousePosition;
// TODO
}
} // namespace priv
} // namespace Window
} // namespace lug
<commit_msg>Remove useless comments<commit_after>#include <lug/Window/Android/WindowImplAndroid.hpp>
#include <mutex>
namespace lug {
namespace Window {
namespace priv {
std::mutex WindowImpl::androidMutex;
std::condition_variable WindowImpl::cv;
std::queue<lug::Window::Event> WindowImpl::events;
AInputQueue* WindowImpl::inputQueue = nullptr;
ANativeWindow* WindowImpl::nativeWindow = nullptr;
ANativeActivity* WindowImpl::activity = nullptr;
WindowImpl::WindowImpl(Window* win) : _parent{win} {}
bool WindowImpl::init(const Window::InitInfo&) {
if (!WindowImpl::nativeWindow) {
std::unique_lock<std::mutex> lk(WindowImpl::androidMutex);
WindowImpl::cv.wait(lk);
}
_parent->_mode.width = ANativeWindow_getWidth(nativeWindow);
_parent->_mode.height = ANativeWindow_getHeight(nativeWindow);
return true;
}
void WindowImpl::close() {}
ANativeWindow* WindowImpl::getWindow() {
return nativeWindow;
}
// Credits to nvidia : https://github.com/NVIDIAGameWorks/GraphicsSamples/blob/master/extensions/src/NvGamepad/android/NvGamepadAndroid.cpp
float WindowImpl::MapCenteredAxis(AInputEvent* event, int32_t axis) {
const float deadZone = (8689.0f / 32768.0f); // 0,2651672363
float value = AMotionEvent_getAxisValue(event, axis, 0);
if (value > deadZone) {
return (value - deadZone) / (1.0f - deadZone);
} else if (value < -deadZone) {
return (value + deadZone) / (1.0f - deadZone);
} else {
return 0.0f;
}
}
int32_t WindowImpl::HandleInput(lug::Window::Event& event, AInputEvent* androidEvent) {
event.touchScreen.drag = false;
event.touchScreen.tap = false;
event.touchScreen.pinch = false;
event.touchScreen.state = lug::Window::TouchScreenEvent::GestureState::None;
if (AInputEvent_getType(androidEvent) == AINPUT_EVENT_TYPE_MOTION) {
event.type = Event::Type::TouchScreenChange;
ndk_helper::GESTURE_STATE doubleTapState = doubletap_detector_.Detect(androidEvent);
ndk_helper::GESTURE_STATE dragState = drag_detector_.Detect(androidEvent);
ndk_helper::GESTURE_STATE pinchState = pinch_detector_.Detect(androidEvent);
// Double tap detector has a priority over other detectors
if (doubleTapState == ndk_helper::GESTURE_STATE_ACTION) {
event.touchScreen.doubleTap = !event.touchScreen.doubleTap;
event.touchScreen.state = static_cast<lug::Window::TouchScreenEvent::GestureState>(doubleTapState);
drag_detector_.GetPointer(event.touchScreen.coordinates[0]);
}
// Drag state
else if (dragState & ndk_helper::GESTURE_STATE_START ||
dragState & ndk_helper::GESTURE_STATE_MOVE ||
dragState & ndk_helper::GESTURE_STATE_END) {
event.touchScreen.drag = true;
event.touchScreen.state = static_cast<lug::Window::TouchScreenEvent::GestureState>(dragState);
drag_detector_.GetPointer(event.touchScreen.coordinates[0]);
}
// Pinch state
else if (pinchState & ndk_helper::GESTURE_STATE_START ||
pinchState & ndk_helper::GESTURE_STATE_MOVE ||
pinchState & ndk_helper::GESTURE_STATE_END) {
event.touchScreen.pinch = true;
event.touchScreen.state = static_cast<lug::Window::TouchScreenEvent::GestureState>(pinchState);
pinch_detector_.GetPointers(event.touchScreen.coordinates[0], event.touchScreen.coordinates[1]);
}
return 1;
}
return 0;
}
bool WindowImpl::pollEvent(lug::Window::Event& event) {
if (inputQueue != nullptr) {
AInputEvent* androidEvent = nullptr;
if (AInputQueue_getEvent(inputQueue, &androidEvent) >= 0) {
if (AInputQueue_preDispatchEvent(inputQueue, androidEvent)) {
return false;
}
HandleInput(event, androidEvent);
LUG_LOG.info("WINDOWS ANDROID event coordinate {} {}", event.touchScreen.coordinates[0].x(), event.touchScreen.coordinates[0].y());
events.push(std::move(event));
AInputQueue_finishEvent(inputQueue, androidEvent, 1);
}
}
if (!events.empty()) {
event = events.front();
events.pop();
return true;
}
return false;
}
void WindowImpl::setKeyRepeat(bool state) {
(void)state;
// TODO
}
void WindowImpl::setMouseCursorVisible(bool visible) {
(void)visible;
// TODO
}
void WindowImpl::setMousePos(const Math::Vec2i& mousePosition) {
(void)mousePosition;
// TODO
}
} // namespace priv
} // namespace Window
} // namespace lug
<|endoftext|> |
<commit_before>/* Luwra
* Minimal-overhead Lua wrapper for C++
*
* Copyright (C) 2015, Ole Krüger <ole@vprsm.de>
*/
#ifndef LUWRA_USERTYPES_H_
#define LUWRA_USERTYPES_H_
#include "common.hpp"
#include "types.hpp"
#include "stack.hpp"
#include <map>
#include <string>
LUWRA_NS_BEGIN
namespace internal {
template <typename T>
using StripUserType = typename std::remove_cv<T>::type;
/**
* User type registry identifiers
*/
template <typename T>
struct UserTypeReg {
/**
* Dummy field which is used because it has a seperate address for each instance of T
*/
static
const int id;
/**
* Registry name for a metatable which is associated with a user type
*/
static
const std::string name;
};
template <typename T>
const int UserTypeReg<T>::id = INT_MAX;
template <typename T>
const std::string UserTypeReg<T>::name = "UD#" + std::to_string(uintptr_t(&id));
/**
* Register a new metatable for a user type T.
*/
template <typename U> static inline
void new_user_type_metatable(State* state) {
using T = StripUserType<U>;
luaL_newmetatable(state, UserTypeReg<T>::name.c_str());
}
/**
* Check if the value at the given index if a user type T.
*/
template <typename U> static inline
StripUserType<U>* check_user_type(State* state, int index) {
using T = StripUserType<U>;
return static_cast<T*>(luaL_checkudata(state, index, UserTypeReg<T>::name.c_str()));
}
/**
* Apply U's metatable for the value at the top of the stack.
*/
template <typename U> static inline
void apply_user_type_meta_table(State* state) {
setMetatable(state, UserTypeReg<StripUserType<U>>::name.c_str());
}
/**
* Lua C function to construct a user type T with parameters A
*/
template <typename U, typename... A> static inline
int construct_user_type(State* state) {
return direct<size_t (A...)>(
state,
&Value<StripUserType<U>&>::template push<A...>,
state
);
}
/**
* Lua C function to destruct a user type T
*/
template <typename U> static inline
int destruct_user_type(State* state) {
using T = StripUserType<U>;
read<T&>(state, 1).~T();
return 0;
}
/**
* Create a string representation for user type T.
*/
template <typename U> static
int stringify_user_type(State* state) {
using T = StripUserType<U>;
return push(
state,
internal::UserTypeReg<T>::name
+ "@"
+ std::to_string(uintptr_t(Value<T*>::read(state, 1)))
);
}
}
/**
* User type
*/
template <typename U>
struct Value<U&> {
using T = internal::StripUserType<U>;
/**
* Reference a user type value on the stack.
* \param state Lua state
* \param n Stack index
* \returns Reference to the user type value
*/
static inline
U& read(State* state, int n) {
// T is unqualified, therefore conversion from T& to U& is allowed
return *internal::check_user_type<T>(state, n);
}
/**
* Construct a user type value on the stack.
* \note Instances created using this specialization are allocated and constructed as full user
* data types in Lua. The default garbage-collecting hook will destruct the user type,
* once it has been marked.
* \param state Lua state
* \param args Constructor arguments
* \returns Number of values that have been pushed onto the stack
*/
template <typename... A> static inline
size_t push(State* state, A&&... args) {
void* mem = lua_newuserdata(state, sizeof(T));
if (!mem) {
luaL_error(state, "Failed to allocate user type");
return -1;
}
// Construct
new (mem) T {std::forward<A>(args)...};
// Apply metatable for unqualified type T
internal::apply_user_type_meta_table<T>(state);
return 1;
}
};
/**
* Construct a user type value on the stack.
* \note Instances created using this specialization are allocated and constructed as full user
* data types in Lua. The default garbage-collecting hook will destruct the user type,
* once it has been marked.
* \param state Lua state
* \param args Constructor arguments
* \returns Reference to the constructed value
*/
template <typename U, typename... A> static inline
internal::StripUserType<U>& construct(State* state, A&&... args) {
using T = internal::StripUserType<U>;
void* mem = lua_newuserdata(state, sizeof(T));
if (!mem) {
luaL_error(state, "Failed to allocate user type");
// 'luaL_error' will not return
}
// Construct
T* value = new (mem) T {std::forward<A>(args)...};
// Apply metatable for unqualified type T
internal::apply_user_type_meta_table<T>(state);
return *value;
}
/**
* User type
*/
template <typename U>
struct Value<U*> {
using T = internal::StripUserType<U>;
/**
* Reference a user type value on the stack.
* \param state Lua state
* \param n Stack index
* \returns Pointer to the user type value.
*/
static inline
U* read(State* state, int n) {
// T is unqualified, therefore conversion from T* to U* is allowed
return internal::check_user_type<T>(state, n);
}
/**
* Copy a value onto the stack. This function behaves exactly as if you would call
* `Value<U&>::push(state, *ptr)`.
* \param state Lua state
* \param ptr Pointer to the user type value
* \returns Number of values that have been pushed
*/
static inline
size_t push(State* state, const T* ptr) {
return Value<T&>::push(state, *ptr);
}
};
using MemberMap = std::map<std::string, Pushable>;
/**
* Register the metatable for user type `T`. This function allows you to register methods
* which are shared across all instances of this type.
*
* By default a garbage-collector hook and string representation function are added as meta methods.
* Both can be overwritten.
*
* \tparam U User type struct or class
*
* \param state Lua state
* \param methods Map of methods
* \param meta_methods Map of meta methods
*/
template <typename U> static inline
void registerUserType(
State* state,
const MemberMap& methods = MemberMap(),
const MemberMap& meta_methods = MemberMap()
) {
using T = internal::StripUserType<U>;
// Setup an appropriate metatable name
internal::new_user_type_metatable<T>(state);
// Register methods
if (methods.size() > 0 && meta_methods.count("__index") == 0) {
push(state, "__index");
lua_newtable(state);
for (auto& method: methods) {
setFields(state, -1, method.first, method.second);
}
lua_rawset(state, -3);
}
// Register garbage-collection hook
if (meta_methods.count("__gc") == 0) {
setFields(state, -1, "__gc", &internal::destruct_user_type<T>);
}
// Register string representation function
if (meta_methods.count("__tostring") == 0) {
setFields(state, -1, "__tostring", &internal::stringify_user_type<T>);
}
// Insert meta methods
for (const auto& metamethod: meta_methods) {
setFields(state, -1, metamethod.first, metamethod.second);
}
// Pop metatable off the stack
lua_pop(state, -1);
}
namespace internal {
template <typename T>
struct UserTypeSignature {
static_assert(
sizeof(T) == -1,
"Parameter to UserTypeSignature is not a valid signature"
);
};
template <typename T, typename... A>
struct UserTypeSignature<T (A...)> {
using UserType = StripUserType<T>;
static inline
void registerConstructor(State* state, const std::string& name) {
setGlobal(state, name, &construct_user_type<UserType, A...>);
}
};
}
/**
* Same as the other `registerUserType` but registers the construtor as well. The template parameter
* is a signature `U(A...)` where `U` is the user type and `A...` its constructor parameters.
*/
template <typename T> static inline
void registerUserType(
State* state,
const std::string& ctor_name,
const MemberMap& methods = MemberMap(),
const MemberMap& meta_methods = MemberMap()
) {
using U = typename internal::UserTypeSignature<T>::UserType;
registerUserType<U>(state, methods, meta_methods);
internal::UserTypeSignature<T>::registerConstructor(state, ctor_name);
}
LUWRA_NS_END
/**
* Generate a `lua_CFunction` wrapper for a constructor.
* \param type Type to instantiate
* \param ... Constructor parameter types
* \return Wrapped function as `lua_CFunction`
*/
#define LUWRA_WRAP_CONSTRUCTOR(type, ...) \
(&luwra::internal::construct_user_type<luwra::internal::StripUserType<type>, __VA_ARGS__>)
/**
* Define the registry name for a user type.
* \param type User type
* \param regname Registry name
*/
#define LUWRA_DEF_REGISTRY_NAME(type, regname) \
template <> struct luwra::internal::UserTypeReg<type> { static const std::string name; }; \
const std::string luwra::internal::UserTypeReg<type>::name = (regname);
#define LUWRA_FIELD(type, name) {__STRING(name), LUWRA_WRAP_FIELD(type::name)}
#define LUWRA_METHOD(type, name) {__STRING(name), LUWRA_WRAP_METHOD(type::name)}
#define LUWRA_FUNCTION(type, name) {__STRING(name), LUWRA_WRAP_FUNCTION(type::name)}
#endif
<commit_msg>Prevent name collisions in the registry<commit_after>/* Luwra
* Minimal-overhead Lua wrapper for C++
*
* Copyright (C) 2015, Ole Krüger <ole@vprsm.de>
*/
#ifndef LUWRA_USERTYPES_H_
#define LUWRA_USERTYPES_H_
#include "common.hpp"
#include "types.hpp"
#include "stack.hpp"
#include <map>
#include <string>
LUWRA_NS_BEGIN
namespace internal {
template <typename T>
using StripUserType = typename std::remove_cv<T>::type;
/**
* User type registry identifiers
*/
template <typename T>
struct UserTypeReg {
/**
* Dummy field which is used because it has a seperate address for each instance of T
*/
static
const int id;
/**
* Registry name for a metatable which is associated with a user type
*/
static
const std::string name;
};
template <typename T>
const int UserTypeReg<T>::id = INT_MAX;
#ifndef LUWRA_REGISTRY_PREFIX
#define LUWRA_REGISTRY_PREFIX "Luwra#"
#endif
template <typename T>
const std::string UserTypeReg<T>::name = LUWRA_REGISTRY_PREFIX + std::to_string(uintptr_t(&id));
/**
* Register a new metatable for a user type T.
*/
template <typename U> static inline
void new_user_type_metatable(State* state) {
using T = StripUserType<U>;
luaL_newmetatable(state, UserTypeReg<T>::name.c_str());
}
/**
* Check if the value at the given index if a user type T.
*/
template <typename U> static inline
StripUserType<U>* check_user_type(State* state, int index) {
using T = StripUserType<U>;
return static_cast<T*>(luaL_checkudata(state, index, UserTypeReg<T>::name.c_str()));
}
/**
* Apply U's metatable for the value at the top of the stack.
*/
template <typename U> static inline
void apply_user_type_meta_table(State* state) {
setMetatable(state, UserTypeReg<StripUserType<U>>::name.c_str());
}
/**
* Lua C function to construct a user type T with parameters A
*/
template <typename U, typename... A> static inline
int construct_user_type(State* state) {
return direct<size_t (A...)>(
state,
&Value<StripUserType<U>&>::template push<A...>,
state
);
}
/**
* Lua C function to destruct a user type T
*/
template <typename U> static inline
int destruct_user_type(State* state) {
using T = StripUserType<U>;
read<T&>(state, 1).~T();
return 0;
}
/**
* Create a string representation for user type T.
*/
template <typename U> static
int stringify_user_type(State* state) {
using T = StripUserType<U>;
return push(
state,
internal::UserTypeReg<T>::name
+ "@"
+ std::to_string(uintptr_t(Value<T*>::read(state, 1)))
);
}
}
/**
* User type
*/
template <typename U>
struct Value<U&> {
using T = internal::StripUserType<U>;
/**
* Reference a user type value on the stack.
* \param state Lua state
* \param n Stack index
* \returns Reference to the user type value
*/
static inline
U& read(State* state, int n) {
// T is unqualified, therefore conversion from T& to U& is allowed
return *internal::check_user_type<T>(state, n);
}
/**
* Construct a user type value on the stack.
* \note Instances created using this specialization are allocated and constructed as full user
* data types in Lua. The default garbage-collecting hook will destruct the user type,
* once it has been marked.
* \param state Lua state
* \param args Constructor arguments
* \returns Number of values that have been pushed onto the stack
*/
template <typename... A> static inline
size_t push(State* state, A&&... args) {
void* mem = lua_newuserdata(state, sizeof(T));
if (!mem) {
luaL_error(state, "Failed to allocate user type");
return -1;
}
// Construct
new (mem) T {std::forward<A>(args)...};
// Apply metatable for unqualified type T
internal::apply_user_type_meta_table<T>(state);
return 1;
}
};
/**
* Construct a user type value on the stack.
* \note Instances created using this specialization are allocated and constructed as full user
* data types in Lua. The default garbage-collecting hook will destruct the user type,
* once it has been marked.
* \param state Lua state
* \param args Constructor arguments
* \returns Reference to the constructed value
*/
template <typename U, typename... A> static inline
internal::StripUserType<U>& construct(State* state, A&&... args) {
using T = internal::StripUserType<U>;
void* mem = lua_newuserdata(state, sizeof(T));
if (!mem) {
luaL_error(state, "Failed to allocate user type");
// 'luaL_error' will not return
}
// Construct
T* value = new (mem) T {std::forward<A>(args)...};
// Apply metatable for unqualified type T
internal::apply_user_type_meta_table<T>(state);
return *value;
}
/**
* User type
*/
template <typename U>
struct Value<U*> {
using T = internal::StripUserType<U>;
/**
* Reference a user type value on the stack.
* \param state Lua state
* \param n Stack index
* \returns Pointer to the user type value.
*/
static inline
U* read(State* state, int n) {
// T is unqualified, therefore conversion from T* to U* is allowed
return internal::check_user_type<T>(state, n);
}
/**
* Copy a value onto the stack. This function behaves exactly as if you would call
* `Value<U&>::push(state, *ptr)`.
* \param state Lua state
* \param ptr Pointer to the user type value
* \returns Number of values that have been pushed
*/
static inline
size_t push(State* state, const T* ptr) {
return Value<T&>::push(state, *ptr);
}
};
using MemberMap = std::map<std::string, Pushable>;
/**
* Register the metatable for user type `T`. This function allows you to register methods
* which are shared across all instances of this type.
*
* By default a garbage-collector hook and string representation function are added as meta methods.
* Both can be overwritten.
*
* \tparam U User type struct or class
*
* \param state Lua state
* \param methods Map of methods
* \param meta_methods Map of meta methods
*/
template <typename U> static inline
void registerUserType(
State* state,
const MemberMap& methods = MemberMap(),
const MemberMap& meta_methods = MemberMap()
) {
using T = internal::StripUserType<U>;
// Setup an appropriate metatable name
internal::new_user_type_metatable<T>(state);
// Register methods
if (methods.size() > 0 && meta_methods.count("__index") == 0) {
push(state, "__index");
lua_newtable(state);
for (auto& method: methods) {
setFields(state, -1, method.first, method.second);
}
lua_rawset(state, -3);
}
// Register garbage-collection hook
if (meta_methods.count("__gc") == 0) {
setFields(state, -1, "__gc", &internal::destruct_user_type<T>);
}
// Register string representation function
if (meta_methods.count("__tostring") == 0) {
setFields(state, -1, "__tostring", &internal::stringify_user_type<T>);
}
// Insert meta methods
for (const auto& metamethod: meta_methods) {
setFields(state, -1, metamethod.first, metamethod.second);
}
// Pop metatable off the stack
lua_pop(state, -1);
}
namespace internal {
template <typename T>
struct UserTypeSignature {
static_assert(
sizeof(T) == -1,
"Parameter to UserTypeSignature is not a valid signature"
);
};
template <typename T, typename... A>
struct UserTypeSignature<T (A...)> {
using UserType = StripUserType<T>;
static inline
void registerConstructor(State* state, const std::string& name) {
setGlobal(state, name, &construct_user_type<UserType, A...>);
}
};
}
/**
* Same as the other `registerUserType` but registers the construtor as well. The template parameter
* is a signature `U(A...)` where `U` is the user type and `A...` its constructor parameters.
*/
template <typename T> static inline
void registerUserType(
State* state,
const std::string& ctor_name,
const MemberMap& methods = MemberMap(),
const MemberMap& meta_methods = MemberMap()
) {
using U = typename internal::UserTypeSignature<T>::UserType;
registerUserType<U>(state, methods, meta_methods);
internal::UserTypeSignature<T>::registerConstructor(state, ctor_name);
}
LUWRA_NS_END
/**
* Generate a `lua_CFunction` wrapper for a constructor.
* \param type Type to instantiate
* \param ... Constructor parameter types
* \return Wrapped function as `lua_CFunction`
*/
#define LUWRA_WRAP_CONSTRUCTOR(type, ...) \
(&luwra::internal::construct_user_type<luwra::internal::StripUserType<type>, __VA_ARGS__>)
/**
* Define the registry name for a user type.
* \param type User type
* \param regname Registry name
*/
#define LUWRA_DEF_REGISTRY_NAME(type, regname) \
template <> struct luwra::internal::UserTypeReg<type> { static const std::string name; }; \
const std::string luwra::internal::UserTypeReg<type>::name = (regname);
#define LUWRA_FIELD(type, name) {__STRING(name), LUWRA_WRAP_FIELD(type::name)}
#define LUWRA_METHOD(type, name) {__STRING(name), LUWRA_WRAP_METHOD(type::name)}
#define LUWRA_FUNCTION(type, name) {__STRING(name), LUWRA_WRAP_FUNCTION(type::name)}
#endif
<|endoftext|> |
<commit_before>/*************************************************************************/
/* image_loader.cpp */
/*************************************************************************/
/* This file is part of: */
/* GODOT ENGINE */
/* https://godotengine.org */
/*************************************************************************/
/* Copyright (c) 2007-2019 Juan Linietsky, Ariel Manzur. */
/* Copyright (c) 2014-2019 Godot Engine contributors (cf. AUTHORS.md) */
/* */
/* Permission is hereby granted, free of charge, to any person obtaining */
/* a copy of this software and associated documentation files (the */
/* "Software"), to deal in the Software without restriction, including */
/* without limitation the rights to use, copy, modify, merge, publish, */
/* distribute, sublicense, and/or sell copies of the Software, and to */
/* permit persons to whom the Software is furnished to do so, subject to */
/* the following conditions: */
/* */
/* The above copyright notice and this permission notice shall be */
/* included in all copies or substantial portions of the Software. */
/* */
/* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, */
/* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF */
/* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.*/
/* IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY */
/* CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, */
/* TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE */
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/*************************************************************************/
#include "image_loader.h"
#include "core/print_string.h"
bool ImageFormatLoader::recognize(const String &p_extension) const {
List<String> extensions;
get_recognized_extensions(&extensions);
for (List<String>::Element *E = extensions.front(); E; E = E->next()) {
if (E->get().nocasecmp_to(p_extension) == 0)
return true;
}
return false;
}
Error ImageLoader::load_image(String p_file, Ref<Image> p_image, FileAccess *p_custom, bool p_force_linear, float p_scale) {
ERR_FAIL_COND_V(p_image.is_null(), ERR_INVALID_PARAMETER);
FileAccess *f = p_custom;
if (!f) {
Error err;
f = FileAccess::open(p_file, FileAccess::READ, &err);
if (!f) {
ERR_PRINTS("Error opening file: " + p_file);
return err;
}
}
String extension = p_file.get_extension();
for (int i = 0; i < loader.size(); i++) {
if (!loader[i]->recognize(extension))
continue;
Error err = loader[i]->load_image(p_image, f, p_force_linear, p_scale);
if (err != ERR_FILE_UNRECOGNIZED) {
if (!p_custom)
memdelete(f);
return err;
}
}
if (!p_custom)
memdelete(f);
return ERR_FILE_UNRECOGNIZED;
}
void ImageLoader::get_recognized_extensions(List<String> *p_extensions) {
for (int i = 0; i < loader.size(); i++) {
loader[i]->get_recognized_extensions(p_extensions);
}
}
ImageFormatLoader *ImageLoader::recognize(const String &p_extension) {
for (int i = 0; i < loader.size(); i++) {
if (loader[i]->recognize(p_extension))
return loader[i];
}
return NULL;
}
Vector<ImageFormatLoader *> ImageLoader::loader;
void ImageLoader::add_image_format_loader(ImageFormatLoader *p_loader) {
loader.push_back(p_loader);
}
void ImageLoader::remove_image_format_loader(ImageFormatLoader *p_loader) {
loader.erase(p_loader);
}
const Vector<ImageFormatLoader *> &ImageLoader::get_image_format_loaders() {
return loader;
}
void ImageLoader::cleanup() {
while (loader.size()) {
remove_image_format_loader(loader[0]);
}
}
/////////////////
RES ResourceFormatLoaderImage::load(const String &p_path, const String &p_original_path, Error *r_error) {
FileAccess *f = FileAccess::open(p_path, FileAccess::READ);
if (!f) {
if (r_error) {
*r_error = ERR_CANT_OPEN;
}
return RES();
}
uint8_t header[4] = { 0, 0, 0, 0 };
f->get_buffer(header, 4);
bool unrecognized = header[0] != 'G' || header[1] != 'D' || header[2] != 'I' || header[3] != 'M';
if (unrecognized) {
memdelete(f);
if (r_error) {
*r_error = ERR_FILE_UNRECOGNIZED;
}
ERR_FAIL_V(RES());
}
String extension = f->get_pascal_string();
int idx = -1;
for (int i = 0; i < ImageLoader::loader.size(); i++) {
if (ImageLoader::loader[i]->recognize(extension)) {
idx = i;
break;
}
}
if (idx == -1) {
memdelete(f);
if (r_error) {
*r_error = ERR_FILE_UNRECOGNIZED;
}
ERR_FAIL_V(RES());
}
Ref<Image> image;
image.instance();
Error err = ImageLoader::loader[idx]->load_image(image, f, false, 1.0);
memdelete(f);
if (err != OK) {
if (r_error) {
*r_error = err;
}
return RES();
}
if (r_error) {
*r_error = OK;
}
return image;
}
void ResourceFormatLoaderImage::get_recognized_extensions(List<String> *p_extensions) const {
p_extensions->push_back("image");
}
bool ResourceFormatLoaderImage::handles_type(const String &p_type) const {
return p_type == "Image";
}
String ResourceFormatLoaderImage::get_resource_type(const String &p_path) const {
return p_path.get_extension().to_lower() == "image" ? "Image" : String();
}
<commit_msg>Print the path of a corrupt image<commit_after>/*************************************************************************/
/* image_loader.cpp */
/*************************************************************************/
/* This file is part of: */
/* GODOT ENGINE */
/* https://godotengine.org */
/*************************************************************************/
/* Copyright (c) 2007-2019 Juan Linietsky, Ariel Manzur. */
/* Copyright (c) 2014-2019 Godot Engine contributors (cf. AUTHORS.md) */
/* */
/* Permission is hereby granted, free of charge, to any person obtaining */
/* a copy of this software and associated documentation files (the */
/* "Software"), to deal in the Software without restriction, including */
/* without limitation the rights to use, copy, modify, merge, publish, */
/* distribute, sublicense, and/or sell copies of the Software, and to */
/* permit persons to whom the Software is furnished to do so, subject to */
/* the following conditions: */
/* */
/* The above copyright notice and this permission notice shall be */
/* included in all copies or substantial portions of the Software. */
/* */
/* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, */
/* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF */
/* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.*/
/* IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY */
/* CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, */
/* TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE */
/* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
/*************************************************************************/
#include "image_loader.h"
#include "core/print_string.h"
bool ImageFormatLoader::recognize(const String &p_extension) const {
List<String> extensions;
get_recognized_extensions(&extensions);
for (List<String>::Element *E = extensions.front(); E; E = E->next()) {
if (E->get().nocasecmp_to(p_extension) == 0)
return true;
}
return false;
}
Error ImageLoader::load_image(String p_file, Ref<Image> p_image, FileAccess *p_custom, bool p_force_linear, float p_scale) {
ERR_FAIL_COND_V(p_image.is_null(), ERR_INVALID_PARAMETER);
FileAccess *f = p_custom;
if (!f) {
Error err;
f = FileAccess::open(p_file, FileAccess::READ, &err);
if (!f) {
ERR_PRINTS("Error opening file: " + p_file);
return err;
}
}
String extension = p_file.get_extension();
for (int i = 0; i < loader.size(); i++) {
if (!loader[i]->recognize(extension))
continue;
Error err = loader[i]->load_image(p_image, f, p_force_linear, p_scale);
if (err != OK) {
ERR_PRINTS("Error loading image: " + p_file);
}
if (err != ERR_FILE_UNRECOGNIZED) {
if (!p_custom)
memdelete(f);
return err;
}
}
if (!p_custom)
memdelete(f);
return ERR_FILE_UNRECOGNIZED;
}
void ImageLoader::get_recognized_extensions(List<String> *p_extensions) {
for (int i = 0; i < loader.size(); i++) {
loader[i]->get_recognized_extensions(p_extensions);
}
}
ImageFormatLoader *ImageLoader::recognize(const String &p_extension) {
for (int i = 0; i < loader.size(); i++) {
if (loader[i]->recognize(p_extension))
return loader[i];
}
return NULL;
}
Vector<ImageFormatLoader *> ImageLoader::loader;
void ImageLoader::add_image_format_loader(ImageFormatLoader *p_loader) {
loader.push_back(p_loader);
}
void ImageLoader::remove_image_format_loader(ImageFormatLoader *p_loader) {
loader.erase(p_loader);
}
const Vector<ImageFormatLoader *> &ImageLoader::get_image_format_loaders() {
return loader;
}
void ImageLoader::cleanup() {
while (loader.size()) {
remove_image_format_loader(loader[0]);
}
}
/////////////////
RES ResourceFormatLoaderImage::load(const String &p_path, const String &p_original_path, Error *r_error) {
FileAccess *f = FileAccess::open(p_path, FileAccess::READ);
if (!f) {
if (r_error) {
*r_error = ERR_CANT_OPEN;
}
return RES();
}
uint8_t header[4] = { 0, 0, 0, 0 };
f->get_buffer(header, 4);
bool unrecognized = header[0] != 'G' || header[1] != 'D' || header[2] != 'I' || header[3] != 'M';
if (unrecognized) {
memdelete(f);
if (r_error) {
*r_error = ERR_FILE_UNRECOGNIZED;
}
ERR_FAIL_V(RES());
}
String extension = f->get_pascal_string();
int idx = -1;
for (int i = 0; i < ImageLoader::loader.size(); i++) {
if (ImageLoader::loader[i]->recognize(extension)) {
idx = i;
break;
}
}
if (idx == -1) {
memdelete(f);
if (r_error) {
*r_error = ERR_FILE_UNRECOGNIZED;
}
ERR_FAIL_V(RES());
}
Ref<Image> image;
image.instance();
Error err = ImageLoader::loader[idx]->load_image(image, f, false, 1.0);
memdelete(f);
if (err != OK) {
if (r_error) {
*r_error = err;
}
return RES();
}
if (r_error) {
*r_error = OK;
}
return image;
}
void ResourceFormatLoaderImage::get_recognized_extensions(List<String> *p_extensions) const {
p_extensions->push_back("image");
}
bool ResourceFormatLoaderImage::handles_type(const String &p_type) const {
return p_type == "Image";
}
String ResourceFormatLoaderImage::get_resource_type(const String &p_path) const {
return p_path.get_extension().to_lower() == "image" ? "Image" : String();
}
<|endoftext|> |
<commit_before>/************************************************************************
*
* Copyright (C) 2017 by Peter Harrison. www.micromouseonline.com
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the
* "Software"), to deal in the Software without restriction, including
* without l> imitation the rights to use, copy, modify, merge, publish,
* distribute, sublicense, and/or sell copies of the Software, and to
* permit persons to whom the Software is furnished to do so, subject to
* the following conditions:
*
* The above copyright notice and this permission notice shall be included
* in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
* IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY
* CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
* TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
************************************************************************/
#include <cstdio>
#include "mazeprinter.h"
static char dirChars[] = "^>v< ";
void printNorthWalls(Maze *maze, uint16_t row) {
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
printf("o");
if (maze->hasWall(cell, NORTH)) {
printf("---");
} else {
printf(" ");
}
}
printf("o\n");
}
void printSouthWalls(Maze *maze, uint16_t row) {
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
printf("o");
if (maze->hasWall(cell, SOUTH)) {
printf("---");
} else {
printf(" ");
}
}
printf("o\n");
}
void MazePrinter::printDirs(Maze *maze) {
printf("\n");
for (auto row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
uint8_t direction = maze->direction(cell);
if (direction > WEST) {
direction = NONE;
}
char c = dirChars[direction];
if (cell == maze->goal()) {
c = '*';
}
printf(" %c ", c);
}
printf("|\n");
}
printSouthWalls(maze, 0);
}
void MazePrinter::printVisitedDirs(Maze *maze) {
printf("\n");
for (auto row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
uint8_t direction = maze->direction(cell);
if (!maze->isVisited(cell)) {
direction = UNSEEN;
}
char c = dirChars[direction];
if (cell == maze->goal()) {
c = '*';
}
printf(" %c ", c);
}
printf("|\n");
}
printSouthWalls(maze, 0);
printf("\n");
}
void MazePrinter::printPlain(Maze *maze) {
printf("\n");
for (auto row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
/* TODO: this is all rather messy */
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
char c = ' ';
if (cell == maze->goal()) {
c = '*';
}
printf(" %c ", c);
}
printf("|\n");
}
printSouthWalls(maze, 0);
}
void MazePrinter::printCDecl(Maze *maze, const char *name) {
printf("\n\nconst uint8_t %s[] = {\n", name);
for (uint16_t x = 0; x < maze->width(); x++) {
printf(" ");
for (uint16_t y = 0; y < maze->width(); y++) {
uint16_t cell = x * maze->width() + y;
printf("0x%02X, ", maze->walls(cell));
}
printf("\n");
}
printf(" };\n\n");
}
void MazePrinter::printRawDecl(Maze *maze, const char *name) {
printf("\n\nconst uint8_t %s[] = {\n", name);
for (uint16_t x = 0; x < maze->width(); x++) {
printf(" ");
for (uint16_t y = 0; y < maze->width(); y++) {
uint16_t cell = x * maze->width() + y;
printf("0x%02X, ", maze->internalWalls(cell));
}
printf("\n");
}
printf(" };\n\n");
}
void MazePrinter::printCosts(Maze *maze) {
printf("\n");
for (auto row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
/* TODO: this is all rather messy */
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
uint16_t cost = maze->cost(cell);
if (cost < MAX_COST) {
printf("%3d", cost);
} else {
printf(" - ");
}
}
printf("|\n");
}
printSouthWalls(maze, 0);
}
<commit_msg>update timestamps<commit_after>/************************************************************************
*
* Copyright (C) 2017 by Peter Harrison. www.micromouseonline.com
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the
* "Software"), to deal in the Software without restriction, including
* without l> imitation the rights to use, copy, modify, merge, publish,
* distribute, sublicense, and/or sell copies of the Software, and to
* permit persons to whom the Software is furnished to do so, subject to
* the following conditions:
*
* The above copyright notice and this permission notice shall be included
* in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
* IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY
* CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
* TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
************************************************************************/
#include <cstdio>
#include "mazeprinter.h"
static char dirChars[] = "^>v< ";
void printNorthWalls(Maze *maze, uint16_t row) {
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
printf("o");
if (maze->hasWall(cell, NORTH)) {
printf("---");
} else {
printf(" ");
}
}
printf("o\n");
}
void printSouthWalls(Maze *maze, uint16_t row) {
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
printf("o");
if (maze->hasWall(cell, SOUTH)) {
printf("---");
} else {
printf(" ");
}
}
printf("o\n");
}
void MazePrinter::printDirs(Maze *maze) {
for (int row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
uint8_t direction = maze->direction(cell);
if (direction > WEST) {
direction = NONE;
}
char c = dirChars[direction];
if (cell == maze->goal()) {
c = '*';
}
printf(" %c ", c);
}
printf("|\n");
}
printSouthWalls(maze, 0);
}
void MazePrinter::printVisitedDirs(Maze *maze) {
for (int row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
uint8_t direction = maze->direction(cell);
if (!maze->isVisited(cell)) {
direction = UNSEEN;
}
char c = dirChars[direction];
if (cell == maze->goal()) {
c = '*';
}
printf(" %c ", c);
}
printf("|\n");
}
printSouthWalls(maze, 0);
printf("\n");
}
void MazePrinter::printPlain(Maze *maze) {
printf("\n");
for (int row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
/* TODO: this is all rather messy */
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
char c = ' ';
if (cell == maze->goal()) {
c = '*';
}
printf(" %c ", c);
}
printf("|\n");
}
printSouthWalls(maze, 0);
}
void MazePrinter::printCDecl(Maze *maze, const char *name) {
printf("\n\nconst uint8_t %s[] = {\n", name);
for (uint16_t x = 0; x < maze->width(); x++) {
printf(" ");
for (uint16_t y = 0; y < maze->width(); y++) {
uint16_t cell = x * maze->width() + y;
printf("0x%02X, ", maze->walls(cell));
}
printf("\n");
}
printf(" };\n\n");
}
void MazePrinter::printRawDecl(Maze *maze, const char *name) {
printf("\n\nconst uint8_t %s[] = {\n", name);
for (uint16_t x = 0; x < maze->width(); x++) {
printf(" ");
for (uint16_t y = 0; y < maze->width(); y++) {
uint16_t cell = x * maze->width() + y;
printf("0x%02X, ", maze->internalWalls(cell));
}
printf("\n");
}
printf(" };\n\n");
}
void MazePrinter::printCosts(Maze *maze) {
printf("\n");
for (int row = static_cast<uint16_t>(maze->width() - 1); row >= 0; row--) {
printNorthWalls(maze, row);
/* TODO: this is all rather messy */
for (uint16_t col = 0; col < maze->width(); col++) {
uint16_t cell = row + maze->width() * col;
if (maze->hasWall(cell, WEST)) {
printf("|");
} else {
printf(" ");
}
uint16_t cost = maze->cost(cell);
if (cost < MAX_COST) {
printf("%3d", cost);
} else {
printf(" - ");
}
}
printf("|\n");
}
printSouthWalls(maze, 0);
}
<|endoftext|> |
<commit_before>/**
* Copyright (c) 2015 Eugene Lazin <4lazin@gmail.com>
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "datetime.h"
#include <cstdio>
#include <boost/regex.hpp>
namespace Akumuli {
//! 1ns interval
typedef std::chrono::nanoseconds DurationT;
static const boost::posix_time::ptime EPOCH = boost::posix_time::from_time_t(0);
aku_Timestamp DateTimeUtil::from_std_chrono(std::chrono::system_clock::time_point timestamp) {
auto duration = timestamp.time_since_epoch();
DurationT result = std::chrono::duration_cast<DurationT>(duration);
return result.count();
}
aku_Timestamp DateTimeUtil::from_boost_ptime(boost::posix_time::ptime timestamp) {
boost::posix_time::time_duration duration = timestamp - EPOCH;
u64 ns = duration.total_nanoseconds();
return ns;
}
boost::posix_time::ptime DateTimeUtil::to_boost_ptime(aku_Timestamp timestamp) {
boost::posix_time::ptime ptime = EPOCH + boost::posix_time::nanoseconds(timestamp);
return ptime;
}
// parse N digits from string
static int parse_n_digits(const char* p, int n, const char* error_message = "can't parse digit") {
int value = 0;
for(int i = 0; i < n; i++) {
char c = *p++;
// c must be in [0x30:0x39] range
if (c > 0x39 || c < 0x30) {
BadDateTimeFormat err(error_message);
BOOST_THROW_EXCEPTION(err);
}
value = value*10 + static_cast<int>(c & 0x0F);
}
return value;
}
aku_Timestamp DateTimeUtil::from_iso_string(const char* iso_str) {
u32 len = static_cast<u32>(std::strlen(iso_str));
// Trim left
while(!isdigit(*iso_str)) {
iso_str++;
len--;
if (len == 0) {
break;
}
}
if (len < 15 || iso_str[8] != 'T') {
// Raw timestamp
aku_Timestamp ts;
char* end;
ts = strtoull(iso_str, &end, 10);
if (errno == ERANGE) {
BadDateTimeFormat error("can't parse unix-timestamp from string");
BOOST_THROW_EXCEPTION(error);
}
long parsed_len = end - iso_str;
if (parsed_len < len) {
BadDateTimeFormat error("unknown timestamp format");
BOOST_THROW_EXCEPTION(error);
}
return ts;
}
if (len < 15) {
BadDateTimeFormat error("bad timestamp format (less then 15 digits)");
BOOST_THROW_EXCEPTION(error);
}
const char* pend = iso_str + len; // should point to zero-terminator
// first four digits - year
const char* p = iso_str;
int year = parse_n_digits(p, 4, "can't parse year from timestamp");
p += 4;
// then 2 month digits
int month = parse_n_digits(p, 2, "can't parse month from timestamp");
p += 2;
// then 2 date digits
int date = parse_n_digits(p, 2, "can't parse date from timestamp");
p += 2;
// then 'T'
if (*p != 'T') {
BadDateTimeFormat error("bad timestamp format, 'T' was expected");
BOOST_THROW_EXCEPTION(error);
}
p++;
// read two hour digits
int hour = parse_n_digits(p, 2, "can't parse hours from timestamp");
p += 2;
// read two minute digits
int minute = parse_n_digits(p, 2, "can't parse minutes from timestamp");
p += 2;
// read seconds
int second = parse_n_digits(p, 2, "can't parse seconds from timestamp");
p += 2;
// optional
int nanoseconds = 0;
if (p != pend) {
// here should go '.' or ',' according to ISO 8601
if (*p != '.' && *p != ',') {
BadDateTimeFormat error("bad timestamp format, ',' or '.' was expected");
BOOST_THROW_EXCEPTION(error);
}
p++;
// we should have at most 9 digits of nanosecond precision representation
int n = pend - p;
nanoseconds = parse_n_digits(p, n, "can't parse fractional part");
for(int i = 9; i --> n;) {
nanoseconds *= 10;
}
}
auto gregorian_date = boost::gregorian::date(year, month, date);
auto time = boost::posix_time::time_duration(hour, minute, second, nanoseconds);
auto pt = boost::posix_time::ptime(gregorian_date, time);
return DateTimeUtil::from_boost_ptime(pt);
}
int DateTimeUtil::to_iso_string(aku_Timestamp ts, char* buffer, size_t buffer_size) {
using namespace boost::gregorian;
using namespace boost::posix_time;
ptime ptime = to_boost_ptime(ts);
date date = ptime.date();
time_duration time = ptime.time_of_day();
gregorian_calendar::ymd_type ymd = gregorian_calendar::from_day_number(date.day_number());
auto fracsec = time.fractional_seconds();
int len = snprintf(buffer, buffer_size, "%04d%02d%02dT%02d%02d%02d.%09d",
// date part
(int)ymd.year, (int)ymd.month, (int)ymd.day,
// time part
(int)time.hours(), (int)time.minutes(), (int)time.seconds(), (int)fracsec
);
if (len < 0 || len == (int)buffer_size) {
return -26;
}
return len + 1;
}
aku_Duration DateTimeUtil::parse_duration(const char* str, size_t size) {
static const char* exp = R"(^(\d+)(n|us|s|min|ms|m|h)?$)";
static boost::regex regex(exp, boost::regex_constants::optimize);
boost::cmatch m;
if (!boost::regex_match(str, m, regex)) {
BadDateTimeFormat bad_duration("bad duration");
BOOST_THROW_EXCEPTION(bad_duration);
}
auto num = m[1];
auto unit = m[2].first;
auto unitlen = m[2].second - m[2].first;
auto K = 0ul;
if (unitlen > 0) {
switch(unit[0]) {
case 'n': // nanosecond
K = 1ul;
break;
case 'u': // microsecond
K = 1000ul;
break;
case 's': // second
K = 1000000000ul;
break;
case 'm':
switch(unitlen) {
case 1:
case 3: // minute
K = 60*1000000000ul;
break;
case 2: // milisecond
K = 1000000ul;
break;
}
break;
case 'h': // hour
K = 60*60*1000000000ul;
break;
}
if (K == 0ul) {
BadDateTimeFormat err("unknown time duration unit");
BOOST_THROW_EXCEPTION(err);
}
} else {
K = 1ul;
}
return K*atoll(num.first);
}
}
<commit_msg>Fix date parser vulnerabilities<commit_after>/**
* Copyright (c) 2015 Eugene Lazin <4lazin@gmail.com>
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "datetime.h"
#include <cstdio>
#include <boost/regex.hpp>
namespace Akumuli {
//! 1ns interval
typedef std::chrono::nanoseconds DurationT;
static const boost::posix_time::ptime EPOCH = boost::posix_time::from_time_t(0);
aku_Timestamp DateTimeUtil::from_std_chrono(std::chrono::system_clock::time_point timestamp) {
auto duration = timestamp.time_since_epoch();
DurationT result = std::chrono::duration_cast<DurationT>(duration);
return result.count();
}
aku_Timestamp DateTimeUtil::from_boost_ptime(boost::posix_time::ptime timestamp) {
boost::posix_time::time_duration duration = timestamp - EPOCH;
u64 ns = duration.total_nanoseconds();
return ns;
}
boost::posix_time::ptime DateTimeUtil::to_boost_ptime(aku_Timestamp timestamp) {
boost::posix_time::ptime ptime = EPOCH + boost::posix_time::nanoseconds(timestamp);
return ptime;
}
// parse N digits from string
static int parse_n_digits(const char* p, int n, const char* error_message = "can't parse digit") {
int value = 0;
for(int i = 0; i < n; i++) {
char c = *p++;
// c must be in [0x30:0x39] range
if (c > 0x39 || c < 0x30) {
BadDateTimeFormat err(error_message);
BOOST_THROW_EXCEPTION(err);
}
value = value*10 + static_cast<int>(c & 0x0F);
}
return value;
}
aku_Timestamp DateTimeUtil::from_iso_string(const char* iso_str) {
u32 len = static_cast<u32>(std::strlen(iso_str));
if (len == 0) {
BadDateTimeFormat error("empty timestamp value");
BOOST_THROW_EXCEPTION(error);
}
// Trim left
while(!isdigit(*iso_str)) {
iso_str++;
len--;
if (len == 0) {
break;
}
}
if (len < 15 || iso_str[8] != 'T') {
// Raw timestamp
aku_Timestamp ts;
char* end;
ts = strtoull(iso_str, &end, 10);
if (errno == ERANGE) {
BadDateTimeFormat error("can't parse unix-timestamp from string");
BOOST_THROW_EXCEPTION(error);
}
long parsed_len = end - iso_str;
if (parsed_len < len) {
BadDateTimeFormat error("unknown timestamp format");
BOOST_THROW_EXCEPTION(error);
}
return ts;
}
if (len < 15) {
BadDateTimeFormat error("bad timestamp format (less then 15 digits)");
BOOST_THROW_EXCEPTION(error);
}
const char* pend = iso_str + len; // should point to zero-terminator
// first four digits - year
const char* p = iso_str;
int year = parse_n_digits(p, 4, "can't parse year from timestamp");
p += 4;
// then 2 month digits
int month = parse_n_digits(p, 2, "can't parse month from timestamp");
p += 2;
// then 2 date digits
int date = parse_n_digits(p, 2, "can't parse date from timestamp");
p += 2;
// then 'T'
if (*p != 'T') {
BadDateTimeFormat error("bad timestamp format, 'T' was expected");
BOOST_THROW_EXCEPTION(error);
}
p++;
// read two hour digits
int hour = parse_n_digits(p, 2, "can't parse hours from timestamp");
p += 2;
// read two minute digits
int minute = parse_n_digits(p, 2, "can't parse minutes from timestamp");
p += 2;
// read seconds
int second = parse_n_digits(p, 2, "can't parse seconds from timestamp");
p += 2;
// optional
int nanoseconds = 0;
if (p != pend) {
// here should go '.' or ',' according to ISO 8601
if (*p != '.' && *p != ',') {
BadDateTimeFormat error("bad timestamp format, ',' or '.' was expected");
BOOST_THROW_EXCEPTION(error);
}
p++;
// we should have at most 9 digits of nanosecond precision representation
int n = pend - p;
nanoseconds = parse_n_digits(p, n, "can't parse fractional part");
for(int i = 9; i --> n;) {
nanoseconds *= 10;
}
}
try {
auto gregorian_date = boost::gregorian::date(year, month, date);
auto time = boost::posix_time::time_duration(hour, minute, second, nanoseconds);
auto pt = boost::posix_time::ptime(gregorian_date, time);
return DateTimeUtil::from_boost_ptime(pt);
} catch (std::out_of_range const& range_error) {
// Invalid date parameter
BadDateTimeFormat error(range_error.what());
BOOST_THROW_EXCEPTION(error);
}
}
int DateTimeUtil::to_iso_string(aku_Timestamp ts, char* buffer, size_t buffer_size) {
using namespace boost::gregorian;
using namespace boost::posix_time;
ptime ptime = to_boost_ptime(ts);
date date = ptime.date();
time_duration time = ptime.time_of_day();
gregorian_calendar::ymd_type ymd = gregorian_calendar::from_day_number(date.day_number());
auto fracsec = time.fractional_seconds();
int len = snprintf(buffer, buffer_size, "%04d%02d%02dT%02d%02d%02d.%09d",
// date part
(int)ymd.year, (int)ymd.month, (int)ymd.day,
// time part
(int)time.hours(), (int)time.minutes(), (int)time.seconds(), (int)fracsec
);
if (len < 0 || len == (int)buffer_size) {
return -26;
}
return len + 1;
}
aku_Duration DateTimeUtil::parse_duration(const char* str, size_t size) {
static const char* exp = R"(^(\d+)(n|us|s|min|ms|m|h)?$)";
static boost::regex regex(exp, boost::regex_constants::optimize);
boost::cmatch m;
if (!boost::regex_match(str, m, regex)) {
BadDateTimeFormat bad_duration("bad duration");
BOOST_THROW_EXCEPTION(bad_duration);
}
auto num = m[1];
auto unit = m[2].first;
auto unitlen = m[2].second - m[2].first;
auto K = 0ul;
if (unitlen > 0) {
switch(unit[0]) {
case 'n': // nanosecond
K = 1ul;
break;
case 'u': // microsecond
K = 1000ul;
break;
case 's': // second
K = 1000000000ul;
break;
case 'm':
switch(unitlen) {
case 1:
case 3: // minute
K = 60*1000000000ul;
break;
case 2: // milisecond
K = 1000000ul;
break;
}
break;
case 'h': // hour
K = 60*60*1000000000ul;
break;
}
if (K == 0ul) {
BadDateTimeFormat err("unknown time duration unit");
BOOST_THROW_EXCEPTION(err);
}
} else {
K = 1ul;
}
return K*atoll(num.first);
}
}
<|endoftext|> |
<commit_before>/**
* @cond ___LICENSE___
*
* Copyright (c) 2016 Koen Visscher, Paul Visscher and individual contributors.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* @endcond
*/
#include "common/environment.h"
#include "common/directory.h"
#include "common/path.h"
#include "preproc/env.h"
#include "api/console.h"
#include "config.h"
#if OS_IS_WINDOWS
# include <windows.h>
#else
# include <unistd.h>
#endif
namespace Path
{
std::string Get( const std::string &path, Type type /*= Type::Game */ )
{
std::string from;
bool resolve = true;
switch ( type )
{
case Path::Type::Program:
from = Path::GetProgramDirectory();
break;
case Path::Type::Data:
from = Path::GetProgramDataDirectory();
break;
case Path::Type::SharedData:
from = Path::GetProgramSharedDataDirectory();
break;
case Path::Type::Temp:
from = Path::GetProgramTempDirectory();
break;
case Path::Type::Editor:
from = Path::GetProgramDirectory();
break;
case Path::Type::None:
resolve = false;
break;
}
return resolve ? Path::ResolveRelative( from, path ) : path;
}
std::string ResolveRelative( const std::string &from, const std::string &to, bool sameRoot /*= true */ )
{
if ( sameRoot )
{
// Just add the relative path to the from path an normalise :)
return Canonical( FixStyle( boost::filesystem::path( Canonical( from ) ).parent_path().generic_string() )
+ Canonical( to ) );
}
else
{
// Cheers - http://stackoverflow.com/questions/10167382/boostfilesystem-get-relative-path
boost::filesystem::path fsFrom, fsTo, result;
fsFrom = boost::filesystem::absolute( from ).parent_path();
fsTo = boost::filesystem::absolute( to );
boost::filesystem::path::const_iterator itrFrom( fsFrom.begin() ), itrTo( fsTo.begin() );
// Find common base
/// @todo itrTo != toEnd always true
for ( boost::filesystem::path::const_iterator toEnd( fsTo.end() ), fromEnd( fsFrom.end() ) ;
itrTo != toEnd && itrFrom != fromEnd && *itrFrom == *itrTo; ++itrFrom, ++itrTo );
// Navigate backwards in directory to reach previously found base
for ( boost::filesystem::path::const_iterator fromEnd( fsFrom.end() ); itrFrom != fromEnd; ++itrFrom )
{
if ( ( *itrFrom ) != "." )
{
result /= "..";
}
}
// Now navigate down the directory branch
for ( ; itrTo != fsTo.end() ; ++itrTo )
{
result /= *itrTo;
}
return Canonical( result.generic_string() );
}
}
std::string FixStyle( const std::string &filePath )
{
const boost::filesystem::path path( filePath );
std::string newPath = path.generic_string();
if ( !( path.has_stem() && path.has_extension() ) )
{
if ( path.empty() || newPath.back() != '/' )
{
newPath += '/';
}
}
#if !(OS_IS_WINDOWS)
newPath = String::Replace( newPath, "\\", "/" );
newPath = String::Replace( newPath, "//", "/" );
#endif
return newPath;
}
std::string Canonical( const std::string &path, bool absolute /*= false */ )
{
#if !(OS_IS_WINDOWS)
newPath = String::Replace( newPath, "\\", "/" );
#endif
if ( ( path == "." || path == "./" ) && !absolute )
{
return path;
}
// Again Cheers - http://stackoverflow.com/questions/1746136/how-do-i-normalize-a-pathname-using-boostfilesystem
boost::filesystem::path fsPath( path );
if ( absolute )
{
fsPath = boost::filesystem::absolute( fsPath );
}
boost::filesystem::path result;
for ( auto it = fsPath.begin(), end = fsPath.end(); it != end; ++it )
{
const std::string part = it->generic_string();
if ( part == ".." )
{
if ( result.filename() == ".." )
{
result /= *it;
}
else
{
if ( result != "" )
{
result = result.parent_path();
}
else
{
result /= "..";
}
}
}
else if ( part == "." )
{
// Ignore
}
else
{
// Just cat other path entries
result /= *it;
}
}
return FixStyle( result.generic_string() );
}
bool IsParent( const std::string &from, const std::string &to )
{
const std::string canFrom = Canonical( from, true );
const std::string canTo = Canonical( to, true );
const std::string relative = Canonical( canFrom + ResolveRelative( canFrom, canTo, false ), true );
return relative.find( canFrom ) == 0;
}
std::string GetFileName( const std::string &path, const bool stripExtension /*= false */ )
{
const boost::filesystem::path fsPath( FixStyle( path ) );
std::string filename;
if ( !stripExtension )
{
filename = fsPath.filename().generic_string();
}
else
{
filename = fsPath.stem().generic_string();
}
return filename;
}
std::string GetDirectory( const std::string &path )
{
return FixStyle( boost::filesystem::path( path ).parent_path().generic_string() );
}
std::string GetExtension( const std::string &filepath, const bool addDot /*= false */ )
{
const std::string fullExtension = boost::filesystem::path( filepath ).extension().generic_string();
return addDot || fullExtension == "" ? fullExtension : fullExtension.substr( 1 );
}
bool HasExtension( const std::string &filepath )
{
return boost::filesystem::path( filepath ).has_extension();
}
std::string GetUniqueFileName( const std::string &extension /*= ".tmp" */ )
{
return FixStyle( boost::filesystem::unique_path( "%%%%-%%%%-%%%%-%%%%" + extension ).generic_string() );
}
std::string GetUniqueDirectory()
{
return FixStyle( boost::filesystem::unique_path( "%%%%-%%%%-%%%%" ).generic_string() );
}
std::string GetTempDirectory()
{
return FixStyle( boost::filesystem::temp_directory_path().generic_string() );
}
std::string GetExeDirectory()
{
return FixStyle( boost::filesystem::path( GetExeFile() ).parent_path().generic_string() );
}
std::string GetExeFile()
{
#if OS_IS_WINDOWS
char result[ MAX_PATH ];
return Canonical( std::string( result, GetModuleFileNameA( nullptr, result, MAX_PATH ) ) );
#elif OS_IS_LINUX
char result[ PATH_MAX ];
size_t count = readlink( "/proc/self/exe", result, PATH_MAX );
return std::string( result, ( count > 0 ) ? count : 0 );
#else
#error
#endif
}
std::string GetDataDirectory()
{
#if OS_IS_WINDOWS
return FixStyle( Environment::GetVariable( "APPDATA" ) );
#elif OS_IS_LINUX
return FixStyle( "~/local/share/" );
#elif OS_IS_MACOS
return "~/Library/Application Support/";
#endif
}
std::string GetSharedDataDirectory()
{
#if OS_IS_WINDOWS
return FixStyle( Environment::GetVariable( "ALLUSERSPROFILE" ) );
#elif OS_IS_LINUX
return "/usr/local/";
#elif OS_IS_MACOS
return "/usr/local/";
#endif
}
std::string GetProgramDirectory()
{
return GetExeDirectory();
}
std::string GetProgramTempDirectory()
{
return String::Format( "%s%s/%s/", GetTempDirectory(), std::string( PROGRAM_COMPANY ), std::string( PROGRAM_NAME ) );
}
std::string GetProgramDataDirectory()
{
return String::Format( "%s%s/%s/", GetDataDirectory(), std::string( PROGRAM_COMPANY ), std::string( PROGRAM_NAME ) );
}
std::string GetProgramSharedDataDirectory()
{
return String::Format( "%s%s/%s/", GetSharedDataDirectory(),
std::string( PROGRAM_COMPANY ),
std::string( PROGRAM_NAME ) );
}
std::vector< boost::filesystem::path > List( const std::string &directory, bool recursive /*= false */ )
{
std::vector< boost::filesystem::path > contents;
if ( !Directory::Exists( directory ) )
{
return contents;
}
if ( recursive )
{
boost::filesystem::recursive_directory_iterator it( directory ), end;
for ( ; it != end; ++it )
{
contents.push_back( *it );
}
}
else
{
boost::filesystem::directory_iterator it( directory ), end;
for ( ; it != end; ++it )
{
contents.push_back( *it );
}
}
return contents;
}
std::vector< std::string > ListContent( const std::string &directory, bool recursive /*= false */ )
{
const std::vector< boost::filesystem::path > contents = List( directory, recursive );
std::vector< std::string > result;
result.reserve( contents.size() );
for ( auto it = contents.begin(), end = contents.end(); it != end; ++it )
{
result.push_back( FixStyle( it->generic_string() ) );
}
return result;
}
std::string GetWorkingDirectory()
{
return Path::FixStyle( boost::filesystem::current_path().generic_string() );
}
bool SetWorkingDirectory( const std::string &workingDirectory )
{
bool success = true;
try
{
boost::filesystem::current_path( workingDirectory );
}
catch ( boost::filesystem::filesystem_error & )
{
success = false;
}
return success;
}
void DeleteAll( const std::string &path )
{
boost::filesystem::remove_all( path );
}
}<commit_msg>Fix variable usage<commit_after>/**
* @cond ___LICENSE___
*
* Copyright (c) 2016 Koen Visscher, Paul Visscher and individual contributors.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* @endcond
*/
#include "common/environment.h"
#include "common/directory.h"
#include "common/path.h"
#include "preproc/env.h"
#include "api/console.h"
#include "config.h"
#if OS_IS_WINDOWS
# include <windows.h>
#else
# include <unistd.h>
#endif
namespace Path
{
std::string Get( const std::string &path, Type type /*= Type::Game */ )
{
std::string from;
bool resolve = true;
switch ( type )
{
case Path::Type::Program:
from = Path::GetProgramDirectory();
break;
case Path::Type::Data:
from = Path::GetProgramDataDirectory();
break;
case Path::Type::SharedData:
from = Path::GetProgramSharedDataDirectory();
break;
case Path::Type::Temp:
from = Path::GetProgramTempDirectory();
break;
case Path::Type::Editor:
from = Path::GetProgramDirectory();
break;
case Path::Type::None:
resolve = false;
break;
}
return resolve ? Path::ResolveRelative( from, path ) : path;
}
std::string ResolveRelative( const std::string &from, const std::string &to, bool sameRoot /*= true */ )
{
if ( sameRoot )
{
// Just add the relative path to the from path an normalise :)
return Canonical( FixStyle( boost::filesystem::path( Canonical( from ) ).parent_path().generic_string() )
+ Canonical( to ) );
}
else
{
// Cheers - http://stackoverflow.com/questions/10167382/boostfilesystem-get-relative-path
boost::filesystem::path fsFrom, fsTo, result;
fsFrom = boost::filesystem::absolute( from ).parent_path();
fsTo = boost::filesystem::absolute( to );
boost::filesystem::path::const_iterator itrFrom( fsFrom.begin() ), itrTo( fsTo.begin() );
// Find common base
/// @todo itrTo != toEnd always true
for ( boost::filesystem::path::const_iterator toEnd( fsTo.end() ), fromEnd( fsFrom.end() ) ;
itrTo != toEnd && itrFrom != fromEnd && *itrFrom == *itrTo; ++itrFrom, ++itrTo );
// Navigate backwards in directory to reach previously found base
for ( boost::filesystem::path::const_iterator fromEnd( fsFrom.end() ); itrFrom != fromEnd; ++itrFrom )
{
if ( ( *itrFrom ) != "." )
{
result /= "..";
}
}
// Now navigate down the directory branch
for ( ; itrTo != fsTo.end() ; ++itrTo )
{
result /= *itrTo;
}
return Canonical( result.generic_string() );
}
}
std::string FixStyle( const std::string &filePath )
{
const boost::filesystem::path path( filePath );
std::string newPath = path.generic_string();
if ( !( path.has_stem() && path.has_extension() ) )
{
if ( path.empty() || newPath.back() != '/' )
{
newPath += '/';
}
}
#if !(OS_IS_WINDOWS)
newPath = String::Replace( newPath, "\\", "/" );
newPath = String::Replace( newPath, "//", "/" );
#endif
return newPath;
}
std::string Canonical( const std::string &opath, bool absolute /*= false */ )
{
std::string path = opath;
#if !(OS_IS_WINDOWS)
path = String::Replace( path, "\\", "/" );
#endif
if ( ( path == "." || path == "./" ) && !absolute )
{
return path;
}
// Again Cheers - http://stackoverflow.com/questions/1746136/how-do-i-normalize-a-pathname-using-boostfilesystem
boost::filesystem::path fsPath( path );
if ( absolute )
{
fsPath = boost::filesystem::absolute( fsPath );
}
boost::filesystem::path result;
for ( auto it = fsPath.begin(), end = fsPath.end(); it != end; ++it )
{
const std::string part = it->generic_string();
if ( part == ".." )
{
if ( result.filename() == ".." )
{
result /= *it;
}
else
{
if ( result != "" )
{
result = result.parent_path();
}
else
{
result /= "..";
}
}
}
else if ( part == "." )
{
// Ignore
}
else
{
// Just cat other path entries
result /= *it;
}
}
return FixStyle( result.generic_string() );
}
bool IsParent( const std::string &from, const std::string &to )
{
const std::string canFrom = Canonical( from, true );
const std::string canTo = Canonical( to, true );
const std::string relative = Canonical( canFrom + ResolveRelative( canFrom, canTo, false ), true );
return relative.find( canFrom ) == 0;
}
std::string GetFileName( const std::string &path, const bool stripExtension /*= false */ )
{
const boost::filesystem::path fsPath( FixStyle( path ) );
std::string filename;
if ( !stripExtension )
{
filename = fsPath.filename().generic_string();
}
else
{
filename = fsPath.stem().generic_string();
}
return filename;
}
std::string GetDirectory( const std::string &path )
{
return FixStyle( boost::filesystem::path( path ).parent_path().generic_string() );
}
std::string GetExtension( const std::string &filepath, const bool addDot /*= false */ )
{
const std::string fullExtension = boost::filesystem::path( filepath ).extension().generic_string();
return addDot || fullExtension == "" ? fullExtension : fullExtension.substr( 1 );
}
bool HasExtension( const std::string &filepath )
{
return boost::filesystem::path( filepath ).has_extension();
}
std::string GetUniqueFileName( const std::string &extension /*= ".tmp" */ )
{
return FixStyle( boost::filesystem::unique_path( "%%%%-%%%%-%%%%-%%%%" + extension ).generic_string() );
}
std::string GetUniqueDirectory()
{
return FixStyle( boost::filesystem::unique_path( "%%%%-%%%%-%%%%" ).generic_string() );
}
std::string GetTempDirectory()
{
return FixStyle( boost::filesystem::temp_directory_path().generic_string() );
}
std::string GetExeDirectory()
{
return FixStyle( boost::filesystem::path( GetExeFile() ).parent_path().generic_string() );
}
std::string GetExeFile()
{
#if OS_IS_WINDOWS
char result[ MAX_PATH ];
return Canonical( std::string( result, GetModuleFileNameA( nullptr, result, MAX_PATH ) ) );
#elif OS_IS_LINUX
char result[ PATH_MAX ];
size_t count = readlink( "/proc/self/exe", result, PATH_MAX );
return std::string( result, ( count > 0 ) ? count : 0 );
#else
#error
#endif
}
std::string GetDataDirectory()
{
#if OS_IS_WINDOWS
return FixStyle( Environment::GetVariable( "APPDATA" ) );
#elif OS_IS_LINUX
return FixStyle( "~/local/share/" );
#elif OS_IS_MACOS
return "~/Library/Application Support/";
#endif
}
std::string GetSharedDataDirectory()
{
#if OS_IS_WINDOWS
return FixStyle( Environment::GetVariable( "ALLUSERSPROFILE" ) );
#elif OS_IS_LINUX
return "/usr/local/";
#elif OS_IS_MACOS
return "/usr/local/";
#endif
}
std::string GetProgramDirectory()
{
return GetExeDirectory();
}
std::string GetProgramTempDirectory()
{
return String::Format( "%s%s/%s/", GetTempDirectory(), std::string( PROGRAM_COMPANY ), std::string( PROGRAM_NAME ) );
}
std::string GetProgramDataDirectory()
{
return String::Format( "%s%s/%s/", GetDataDirectory(), std::string( PROGRAM_COMPANY ), std::string( PROGRAM_NAME ) );
}
std::string GetProgramSharedDataDirectory()
{
return String::Format( "%s%s/%s/", GetSharedDataDirectory(),
std::string( PROGRAM_COMPANY ),
std::string( PROGRAM_NAME ) );
}
std::vector< boost::filesystem::path > List( const std::string &directory, bool recursive /*= false */ )
{
std::vector< boost::filesystem::path > contents;
if ( !Directory::Exists( directory ) )
{
return contents;
}
if ( recursive )
{
boost::filesystem::recursive_directory_iterator it( directory ), end;
for ( ; it != end; ++it )
{
contents.push_back( *it );
}
}
else
{
boost::filesystem::directory_iterator it( directory ), end;
for ( ; it != end; ++it )
{
contents.push_back( *it );
}
}
return contents;
}
std::vector< std::string > ListContent( const std::string &directory, bool recursive /*= false */ )
{
const std::vector< boost::filesystem::path > contents = List( directory, recursive );
std::vector< std::string > result;
result.reserve( contents.size() );
for ( auto it = contents.begin(), end = contents.end(); it != end; ++it )
{
result.push_back( FixStyle( it->generic_string() ) );
}
return result;
}
std::string GetWorkingDirectory()
{
return Path::FixStyle( boost::filesystem::current_path().generic_string() );
}
bool SetWorkingDirectory( const std::string &workingDirectory )
{
bool success = true;
try
{
boost::filesystem::current_path( workingDirectory );
}
catch ( boost::filesystem::filesystem_error & )
{
success = false;
}
return success;
}
void DeleteAll( const std::string &path )
{
boost::filesystem::remove_all( path );
}
}<|endoftext|> |
<commit_before>/*
This file is part of cpp-ethereum.
cpp-ethereum is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
cpp-ethereum is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with cpp-ethereum. If not, see <http://www.gnu.org/licenses/>.
*/
/** @file CommonIO.cpp
* @author Gav Wood <i@gavwood.com>
* @date 2014
*/
#include "CommonIO.h"
#include <iostream>
#include <cstdlib>
#include <fstream>
#include <stdio.h>
#ifdef _WIN32
#include <windows.h>
#else
#include <termios.h>
#endif
#include <boost/filesystem.hpp>
#include "Exceptions.h"
using namespace std;
using namespace dev;
string dev::memDump(bytes const& _bytes, unsigned _width, bool _html)
{
stringstream ret;
if (_html)
ret << "<pre style=\"font-family: Monospace,Lucida Console,Courier,Courier New,sans-serif; font-size: small\">";
for (unsigned i = 0; i < _bytes.size(); i += _width)
{
ret << hex << setw(4) << setfill('0') << i << " ";
for (unsigned j = i; j < i + _width; ++j)
if (j < _bytes.size())
if (_bytes[j] >= 32 && _bytes[j] < 127)
if ((char)_bytes[j] == '<' && _html)
ret << "<";
else if ((char)_bytes[j] == '&' && _html)
ret << "&";
else
ret << (char)_bytes[j];
else
ret << '?';
else
ret << ' ';
ret << " ";
for (unsigned j = i; j < i + _width && j < _bytes.size(); ++j)
ret << setfill('0') << setw(2) << hex << (unsigned)_bytes[j] << " ";
ret << "\n";
}
if (_html)
ret << "</pre>";
return ret.str();
}
template <typename _T>
inline _T contentsGeneric(std::string const& _file)
{
_T ret;
size_t const c_elementSize = sizeof(typename _T::value_type);
std::ifstream is(_file, std::ifstream::binary);
if (!is)
return ret;
// get length of file:
is.seekg(0, is.end);
streamoff length = is.tellg();
if (length == 0)
return ret; // do not read empty file (MSVC does not like it)
is.seekg(0, is.beg);
ret.resize((length + c_elementSize - 1) / c_elementSize);
is.read(const_cast<char*>(reinterpret_cast<char const*>(ret.data())), length);
return ret;
}
bytes dev::contents(string const& _file)
{
return contentsGeneric<bytes>(_file);
}
string dev::contentsString(string const& _file)
{
return contentsGeneric<string>(_file);
}
void dev::writeFile(std::string const& _file, bytesConstRef _data, bool _writeDeleteRename)
{
if (_writeDeleteRename)
{
namespace fs = boost::filesystem;
fs::path tempPath = fs::unique_path(_file + "-%%%%%%");
writeFile(tempPath.string(), _data, false);
// will delete _file if it exists
fs::rename(tempPath, _file);
}
else
{
ofstream s(_file, ios::trunc | ios::binary);
s.write(reinterpret_cast<char const*>(_data.data()), _data.size());
if (!s)
BOOST_THROW_EXCEPTION(FileError());
}
}
std::string dev::getPassword(std::string const& _prompt)
{
#if WIN32
cout << _prompt << flush;
// Get current Console input flags
HANDLE hStdin;
DWORD fdwSaveOldMode;
if ((hStdin = GetStdHandle(STD_INPUT_HANDLE)) == INVALID_HANDLE_VALUE)
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("GetStdHandle"));
if (!GetConsoleMode(hStdin, &fdwSaveOldMode))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("GetConsoleMode"));
// Set console flags to no echo
if (!SetConsoleMode(hStdin, fdwSaveOldMode & (~ENABLE_ECHO_INPUT)))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("SetConsoleMode"));
// Read the string
std::string ret;
std::getline(cin, ret);
// Restore old input mode
if (!SetConsoleMode(hStdin, fdwSaveOldMode))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("SetConsoleMode"));
return ret;
#else
struct termios oflags;
struct termios nflags;
char password[256];
// disable echo in the terminal
tcgetattr(fileno(stdin), &oflags);
nflags = oflags;
nflags.c_lflag &= ~ECHO;
nflags.c_lflag |= ECHONL;
if (tcsetattr(fileno(stdin), TCSANOW, &nflags) != 0)
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("tcsetattr"));
printf("%s", _prompt.c_str());
if (!fgets(password, sizeof(password), stdin))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("fgets"));
password[strlen(password) - 1] = 0;
// restore terminal
if (tcsetattr(fileno(stdin), TCSANOW, &oflags) != 0)
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("tcsetattr"));
return password;
#endif
}
<commit_msg>add filename as exception information<commit_after>/*
This file is part of cpp-ethereum.
cpp-ethereum is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
cpp-ethereum is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with cpp-ethereum. If not, see <http://www.gnu.org/licenses/>.
*/
/** @file CommonIO.cpp
* @author Gav Wood <i@gavwood.com>
* @date 2014
*/
#include "CommonIO.h"
#include <iostream>
#include <cstdlib>
#include <fstream>
#include <stdio.h>
#ifdef _WIN32
#include <windows.h>
#else
#include <termios.h>
#endif
#include <boost/filesystem.hpp>
#include "Exceptions.h"
using namespace std;
using namespace dev;
string dev::memDump(bytes const& _bytes, unsigned _width, bool _html)
{
stringstream ret;
if (_html)
ret << "<pre style=\"font-family: Monospace,Lucida Console,Courier,Courier New,sans-serif; font-size: small\">";
for (unsigned i = 0; i < _bytes.size(); i += _width)
{
ret << hex << setw(4) << setfill('0') << i << " ";
for (unsigned j = i; j < i + _width; ++j)
if (j < _bytes.size())
if (_bytes[j] >= 32 && _bytes[j] < 127)
if ((char)_bytes[j] == '<' && _html)
ret << "<";
else if ((char)_bytes[j] == '&' && _html)
ret << "&";
else
ret << (char)_bytes[j];
else
ret << '?';
else
ret << ' ';
ret << " ";
for (unsigned j = i; j < i + _width && j < _bytes.size(); ++j)
ret << setfill('0') << setw(2) << hex << (unsigned)_bytes[j] << " ";
ret << "\n";
}
if (_html)
ret << "</pre>";
return ret.str();
}
template <typename _T>
inline _T contentsGeneric(std::string const& _file)
{
_T ret;
size_t const c_elementSize = sizeof(typename _T::value_type);
std::ifstream is(_file, std::ifstream::binary);
if (!is)
return ret;
// get length of file:
is.seekg(0, is.end);
streamoff length = is.tellg();
if (length == 0)
return ret; // do not read empty file (MSVC does not like it)
is.seekg(0, is.beg);
ret.resize((length + c_elementSize - 1) / c_elementSize);
is.read(const_cast<char*>(reinterpret_cast<char const*>(ret.data())), length);
return ret;
}
bytes dev::contents(string const& _file)
{
return contentsGeneric<bytes>(_file);
}
string dev::contentsString(string const& _file)
{
return contentsGeneric<string>(_file);
}
void dev::writeFile(std::string const& _file, bytesConstRef _data, bool _writeDeleteRename)
{
if (_writeDeleteRename)
{
namespace fs = boost::filesystem;
fs::path tempPath = fs::unique_path(_file + "-%%%%%%");
writeFile(tempPath.string(), _data, false);
// will delete _file if it exists
fs::rename(tempPath, _file);
}
else
{
ofstream s(_file, ios::trunc | ios::binary);
s.write(reinterpret_cast<char const*>(_data.data()), _data.size());
if (!s)
BOOST_THROW_EXCEPTION(FileError() << errinfo_comment("Could not write to file: " + _file));
}
}
std::string dev::getPassword(std::string const& _prompt)
{
#if WIN32
cout << _prompt << flush;
// Get current Console input flags
HANDLE hStdin;
DWORD fdwSaveOldMode;
if ((hStdin = GetStdHandle(STD_INPUT_HANDLE)) == INVALID_HANDLE_VALUE)
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("GetStdHandle"));
if (!GetConsoleMode(hStdin, &fdwSaveOldMode))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("GetConsoleMode"));
// Set console flags to no echo
if (!SetConsoleMode(hStdin, fdwSaveOldMode & (~ENABLE_ECHO_INPUT)))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("SetConsoleMode"));
// Read the string
std::string ret;
std::getline(cin, ret);
// Restore old input mode
if (!SetConsoleMode(hStdin, fdwSaveOldMode))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("SetConsoleMode"));
return ret;
#else
struct termios oflags;
struct termios nflags;
char password[256];
// disable echo in the terminal
tcgetattr(fileno(stdin), &oflags);
nflags = oflags;
nflags.c_lflag &= ~ECHO;
nflags.c_lflag |= ECHONL;
if (tcsetattr(fileno(stdin), TCSANOW, &nflags) != 0)
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("tcsetattr"));
printf("%s", _prompt.c_str());
if (!fgets(password, sizeof(password), stdin))
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("fgets"));
password[strlen(password) - 1] = 0;
// restore terminal
if (tcsetattr(fileno(stdin), TCSANOW, &oflags) != 0)
BOOST_THROW_EXCEPTION(ExternalFunctionFailure("tcsetattr"));
return password;
#endif
}
<|endoftext|> |
<commit_before>// Copyright (c) 2019 ASMlover. All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list ofconditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in
// the documentation and/or other materialsprovided with the
// distribution.
//
// 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 HOLDER 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 <cassert>
#include <cstring>
#include <iostream>
#include <sstream>
#include "vm.hh"
#include "object.hh"
namespace nyx {
inline int power_of_2ceil(int n) {
--n;
n |= n >> 1;
n |= n >> 2;
n |= n >> 4;
n |= n >> 8;
n |= n >> 16;
++n;
return n;
}
static u32_t string_hash(const char* s, int n) {
// FNV-1a hash. See: http://www.isthe.com/chongo/tech/comp/fnv/
u32_t hash{2166136261u};
for (int i = 0; i < n; ++i) {
hash ^= s[i];
hash *= 16777619;
}
return hash;
}
str_t BaseObject::type_name(void) const {
switch (type_) {
case ObjType::STRING: return "<string>";
case ObjType::CLOSURE: return "<closure>";
case ObjType::FUNCTION: return "<function>";
case ObjType::NATIVE: return "<native>";
case ObjType::UPVALUE: return "<upvalue>";
case ObjType::CLASS: return "<class>";
case ObjType::INSTANCE: return "<instance>";
case ObjType::BOUND_METHOD: return "<bound method>";
}
return "<unknown>";
}
std::ostream& operator<<(std::ostream& out, BaseObject* obj) {
return out << obj->stringify();
}
void gray_table(VM& vm, table_t& tbl) {
for (auto& t : tbl)
vm.gray_value(t.second);
}
void remove_table_undark(table_t& tbl) {
for (auto it = tbl.begin(); it != tbl.end();) {
if (!it->second.as_object()->is_dark())
tbl.erase(it++);
else
++it;
}
}
StringObject::StringObject(const char* s, int n, u32_t hash, bool copy)
: BaseObject(ObjType::STRING)
, count_(n)
, hash_(hash) {
if (copy) {
chars_ = new char[count_ + 1];
if (s != nullptr)
memcpy(chars_, s, n);
chars_[count_] = 0;
}
else {
chars_ = const_cast<char*>(s);
}
}
StringObject::~StringObject(void) {
if (chars_ != nullptr)
delete [] chars_;
}
sz_t StringObject::size_bytes(void) const {
return sizeof(*this) + sizeof(char) * count_;
}
str_t StringObject::stringify(void) const {
return chars_;
}
bool StringObject::is_equal(BaseObject* other) const {
return false;
// auto* r = Xptr::down<StringObject>(other);
// return (hash_ == r->hash_ && count_ == r->count_
// && memcmp(chars_, r->chars_, count_) == 0);
}
void StringObject::blacken(VM&) {
}
StringObject* StringObject::create(VM& vm, const str_t& s) {
return create(vm, s.c_str(), static_cast<int>(s.size()));
}
StringObject* StringObject::create(VM& vm, const char* s, int n) {
auto hash = string_hash(s, n);
if (auto v = vm.get_intern_string(hash); v)
return *v;
auto* o = new StringObject(s, n, hash);
vm.set_intern_string(hash, o);
vm.append_object(o);
return o;
}
StringObject* StringObject::concat(VM& vm, StringObject* a, StringObject* b) {
int count = 0;
count += a == nullptr ? 0 : a->count();
count += b == nullptr ? 0 : b->count();
char* chars = new char[count + 1];
int offset = 0;
if (a != nullptr) {
memcpy(chars, a->chars(), a->count());
offset = a->count();
}
if (b != nullptr)
memcpy(chars + offset, b->chars(), b->count());
chars[count] = 0;
u32_t hash = string_hash(chars, count);
if (auto v = vm.get_intern_string(hash); v) {
delete [] chars;
return *v;
}
auto* o = new StringObject(chars, count, hash, true);
vm.set_intern_string(hash, o);
vm.append_object(o);
return o;
}
FunctionObject::FunctionObject(void)
: BaseObject(ObjType::FUNCTION) {
}
FunctionObject::~FunctionObject(void) {
}
sz_t FunctionObject::size_bytes(void) const {
return sizeof(*this);
}
str_t FunctionObject::stringify(void) const {
std::stringstream ss;
ss << "<fn `" << this << "`>";
return ss.str();
}
bool FunctionObject::is_equal(BaseObject*) const {
return false;
}
void FunctionObject::blacken(VM& vm) {
chunk_.iter_constants([&vm](const Value& v) { vm.gray_value(v); });
vm.gray_object(name_);
}
FunctionObject* FunctionObject::create(VM& vm) {
auto* o = new FunctionObject();
vm.append_object(o);
return o;
}
sz_t NativeObject::size_bytes(void) const {
return sizeof(*this);
}
str_t NativeObject::stringify(void) const {
std::stringstream ss;
ss << "<native `" << &fn_ << "`>";
return ss.str();
}
bool NativeObject::is_equal(BaseObject* other) const {
return false;
}
void NativeObject::blacken(VM& vm) {
}
NativeObject* NativeObject::create(VM& vm, const NativeFunction& fn) {
auto* o = new NativeObject(fn);
vm.append_object(o);
return o;
}
NativeObject* NativeObject::create(VM& vm, NativeFunction&& fn) {
auto* o = new NativeObject(std::move(fn));
vm.append_object(o);
return o;
}
sz_t UpvalueObject::size_bytes(void) const {
return sizeof(*this);
}
str_t UpvalueObject::stringify(void) const {
return "upvalue";
}
bool UpvalueObject::is_equal(BaseObject* other) const {
return false;
}
void UpvalueObject::blacken(VM& vm) {
vm.gray_value(closed_);
}
UpvalueObject* UpvalueObject::create(VM& vm, Value* slot) {
auto* o = new UpvalueObject(slot);
vm.append_object(o);
return o;
}
ClosureObject::ClosureObject(FunctionObject* fn)
: BaseObject(ObjType::CLOSURE)
, function_(fn)
, upvalues_count_(fn->upvalues_count()) {
using UpvalueX = UpvalueObject*;
upvalues_ = new UpvalueX[fn->upvalues_count()];
for (int i = 0; i < fn->upvalues_count(); ++i)
upvalues_[i] = nullptr;
}
ClosureObject::~ClosureObject(void) {
if (upvalues_ != nullptr)
delete [] upvalues_;
}
sz_t ClosureObject::size_bytes(void) const {
return sizeof(*this) + sizeof(UpvalueObject*) * function_->upvalues_count();
}
str_t ClosureObject::stringify(void) const {
std::stringstream ss;
ss << "<fn `" << this << "`>";
return ss.str();
}
bool ClosureObject::is_equal(BaseObject* other) const {
return false;
}
void ClosureObject::blacken(VM& vm) {
vm.gray_object(function_);
for (int i = 0; i < upvalues_count_; ++i)
vm.gray_object(upvalues_[i]);
}
ClosureObject* ClosureObject::create(VM& vm, FunctionObject* fn) {
auto* o = new ClosureObject(fn);
vm.append_object(o);
return o;
}
ClassObject::ClassObject(
StringObject* name, ClassObject* superclass)
: BaseObject(ObjType::CLASS)
, name_(name)
, superclass_(superclass) {
}
ClassObject::~ClassObject(void) {
}
void ClassObject::inherit_from(ClassObject* superclass) {
for (auto& meth : superclass->methods_)
methods_[meth.first] = meth.second;
}
sz_t ClassObject::size_bytes(void) const {
return sizeof(*this);
}
str_t ClassObject::stringify(void) const {
return name_ != nullptr ? name_->chars() : "class";
}
bool ClassObject::is_equal(BaseObject* other) const {
return false;
}
void ClassObject::blacken(VM& vm) {
vm.gray_object(name_);
vm.gray_object(superclass_);
gray_table(vm, methods_);
}
ClassObject* ClassObject::create(
VM& vm, StringObject* name, ClassObject* superclass) {
auto* o = new ClassObject(name, superclass);
vm.append_object(o);
return o;
}
InstanceObject::InstanceObject(ClassObject* klass)
: BaseObject(ObjType::INSTANCE) , class_(klass) {
}
InstanceObject::~InstanceObject(void) {
}
sz_t InstanceObject::size_bytes(void) const {
return sizeof(*this);
}
str_t InstanceObject::stringify(void) const {
std::stringstream ss;
ss << "<`" << class_->stringify() << "` instance>";
return ss.str();
}
bool InstanceObject::is_equal(BaseObject* other) const {
return false;
}
void InstanceObject::blacken(VM& vm) {
vm.gray_object(class_);
gray_table(vm, fields_);
}
InstanceObject* InstanceObject::create(VM& vm, ClassObject* klass) {
auto* o = new InstanceObject(klass);
vm.append_object(o);
return o;
}
BoundMethodObject::BoundMethodObject(const Value& receiver, ClosureObject* method)
: BaseObject(ObjType::BOUND_METHOD)
, receiver_(receiver)
, method_(method) {
}
BoundMethodObject::~BoundMethodObject(void) {
}
sz_t BoundMethodObject::size_bytes(void) const {
return sizeof(*this);
}
str_t BoundMethodObject::stringify(void) const {
std::stringstream ss;
ss << "<fn `" << this << "`";
return ss.str();
}
bool BoundMethodObject::is_equal(BaseObject* other) const {
return false;
}
void BoundMethodObject::blacken(VM& vm) {
vm.gray_value(receiver_);
vm.gray_object(method_);
}
BoundMethodObject* BoundMethodObject::create(
VM& vm, const Value& receiver, ClosureObject* method) {
auto* o = new BoundMethodObject(receiver, method);
vm.append_object(o);
return o;
}
}
<commit_msg>:construction: chore(object): updated the object print<commit_after>// Copyright (c) 2019 ASMlover. All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list ofconditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in
// the documentation and/or other materialsprovided with the
// distribution.
//
// 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 HOLDER 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 <cassert>
#include <cstring>
#include <iostream>
#include <sstream>
#include "vm.hh"
#include "object.hh"
namespace nyx {
inline int power_of_2ceil(int n) {
--n;
n |= n >> 1;
n |= n >> 2;
n |= n >> 4;
n |= n >> 8;
n |= n >> 16;
++n;
return n;
}
static u32_t string_hash(const char* s, int n) {
// FNV-1a hash. See: http://www.isthe.com/chongo/tech/comp/fnv/
u32_t hash{2166136261u};
for (int i = 0; i < n; ++i) {
hash ^= s[i];
hash *= 16777619;
}
return hash;
}
str_t BaseObject::type_name(void) const {
switch (type_) {
case ObjType::STRING: return "<string>";
case ObjType::CLOSURE: return "<closure>";
case ObjType::FUNCTION: return "<function>";
case ObjType::NATIVE: return "<native>";
case ObjType::UPVALUE: return "<upvalue>";
case ObjType::CLASS: return "<class>";
case ObjType::INSTANCE: return "<instance>";
case ObjType::BOUND_METHOD: return "<bound method>";
}
return "<unknown>";
}
std::ostream& operator<<(std::ostream& out, BaseObject* obj) {
return out << obj->stringify();
}
void gray_table(VM& vm, table_t& tbl) {
for (auto& t : tbl)
vm.gray_value(t.second);
}
void remove_table_undark(table_t& tbl) {
for (auto it = tbl.begin(); it != tbl.end();) {
if (!it->second.as_object()->is_dark())
tbl.erase(it++);
else
++it;
}
}
StringObject::StringObject(const char* s, int n, u32_t hash, bool copy)
: BaseObject(ObjType::STRING)
, count_(n)
, hash_(hash) {
if (copy) {
chars_ = new char[count_ + 1];
if (s != nullptr)
memcpy(chars_, s, n);
chars_[count_] = 0;
}
else {
chars_ = const_cast<char*>(s);
}
}
StringObject::~StringObject(void) {
if (chars_ != nullptr)
delete [] chars_;
}
sz_t StringObject::size_bytes(void) const {
return sizeof(*this) + sizeof(char) * count_;
}
str_t StringObject::stringify(void) const {
return chars_;
}
bool StringObject::is_equal(BaseObject* other) const {
return false;
// auto* r = Xptr::down<StringObject>(other);
// return (hash_ == r->hash_ && count_ == r->count_
// && memcmp(chars_, r->chars_, count_) == 0);
}
void StringObject::blacken(VM&) {
}
StringObject* StringObject::create(VM& vm, const str_t& s) {
return create(vm, s.c_str(), static_cast<int>(s.size()));
}
StringObject* StringObject::create(VM& vm, const char* s, int n) {
auto hash = string_hash(s, n);
if (auto v = vm.get_intern_string(hash); v)
return *v;
auto* o = new StringObject(s, n, hash);
vm.set_intern_string(hash, o);
vm.append_object(o);
return o;
}
StringObject* StringObject::concat(VM& vm, StringObject* a, StringObject* b) {
int count = 0;
count += a == nullptr ? 0 : a->count();
count += b == nullptr ? 0 : b->count();
char* chars = new char[count + 1];
int offset = 0;
if (a != nullptr) {
memcpy(chars, a->chars(), a->count());
offset = a->count();
}
if (b != nullptr)
memcpy(chars + offset, b->chars(), b->count());
chars[count] = 0;
u32_t hash = string_hash(chars, count);
if (auto v = vm.get_intern_string(hash); v) {
delete [] chars;
return *v;
}
auto* o = new StringObject(chars, count, hash, true);
vm.set_intern_string(hash, o);
vm.append_object(o);
return o;
}
FunctionObject::FunctionObject(void)
: BaseObject(ObjType::FUNCTION) {
}
FunctionObject::~FunctionObject(void) {
}
sz_t FunctionObject::size_bytes(void) const {
return sizeof(*this);
}
str_t FunctionObject::stringify(void) const {
std::stringstream ss;
ss << "<fn `" << (name_ != nullptr ? name_->chars() : "<top>") << "`>";
return ss.str();
}
bool FunctionObject::is_equal(BaseObject*) const {
return false;
}
void FunctionObject::blacken(VM& vm) {
chunk_.iter_constants([&vm](const Value& v) { vm.gray_value(v); });
vm.gray_object(name_);
}
FunctionObject* FunctionObject::create(VM& vm) {
auto* o = new FunctionObject();
vm.append_object(o);
return o;
}
sz_t NativeObject::size_bytes(void) const {
return sizeof(*this);
}
str_t NativeObject::stringify(void) const {
std::stringstream ss;
ss << "<native `" << &fn_ << "`>";
return ss.str();
}
bool NativeObject::is_equal(BaseObject* other) const {
return false;
}
void NativeObject::blacken(VM& vm) {
}
NativeObject* NativeObject::create(VM& vm, const NativeFunction& fn) {
auto* o = new NativeObject(fn);
vm.append_object(o);
return o;
}
NativeObject* NativeObject::create(VM& vm, NativeFunction&& fn) {
auto* o = new NativeObject(std::move(fn));
vm.append_object(o);
return o;
}
sz_t UpvalueObject::size_bytes(void) const {
return sizeof(*this);
}
str_t UpvalueObject::stringify(void) const {
return "<upvalue>";
}
bool UpvalueObject::is_equal(BaseObject* other) const {
return false;
}
void UpvalueObject::blacken(VM& vm) {
vm.gray_value(closed_);
}
UpvalueObject* UpvalueObject::create(VM& vm, Value* slot) {
auto* o = new UpvalueObject(slot);
vm.append_object(o);
return o;
}
ClosureObject::ClosureObject(FunctionObject* fn)
: BaseObject(ObjType::CLOSURE)
, function_(fn)
, upvalues_count_(fn->upvalues_count()) {
using UpvalueX = UpvalueObject*;
upvalues_ = new UpvalueX[fn->upvalues_count()];
for (int i = 0; i < fn->upvalues_count(); ++i)
upvalues_[i] = nullptr;
}
ClosureObject::~ClosureObject(void) {
if (upvalues_ != nullptr)
delete [] upvalues_;
}
sz_t ClosureObject::size_bytes(void) const {
return sizeof(*this) + sizeof(UpvalueObject*) * function_->upvalues_count();
}
str_t ClosureObject::stringify(void) const {
std::stringstream ss;
ss << "<fn `"
<< (function_->name() == nullptr ? "<top>" : function_->name()->chars())
<< "`>";
return ss.str();
}
bool ClosureObject::is_equal(BaseObject* other) const {
return false;
}
void ClosureObject::blacken(VM& vm) {
vm.gray_object(function_);
for (int i = 0; i < upvalues_count_; ++i)
vm.gray_object(upvalues_[i]);
}
ClosureObject* ClosureObject::create(VM& vm, FunctionObject* fn) {
auto* o = new ClosureObject(fn);
vm.append_object(o);
return o;
}
ClassObject::ClassObject(
StringObject* name, ClassObject* superclass)
: BaseObject(ObjType::CLASS)
, name_(name)
, superclass_(superclass) {
}
ClassObject::~ClassObject(void) {
}
void ClassObject::inherit_from(ClassObject* superclass) {
for (auto& meth : superclass->methods_)
methods_[meth.first] = meth.second;
}
sz_t ClassObject::size_bytes(void) const {
return sizeof(*this);
}
str_t ClassObject::stringify(void) const {
std::stringstream ss;
ss << "<`" << name_->chars() << "` class>";
return ss.str();
}
bool ClassObject::is_equal(BaseObject* other) const {
return false;
}
void ClassObject::blacken(VM& vm) {
vm.gray_object(name_);
vm.gray_object(superclass_);
gray_table(vm, methods_);
}
ClassObject* ClassObject::create(
VM& vm, StringObject* name, ClassObject* superclass) {
auto* o = new ClassObject(name, superclass);
vm.append_object(o);
return o;
}
InstanceObject::InstanceObject(ClassObject* klass)
: BaseObject(ObjType::INSTANCE) , class_(klass) {
}
InstanceObject::~InstanceObject(void) {
}
sz_t InstanceObject::size_bytes(void) const {
return sizeof(*this);
}
str_t InstanceObject::stringify(void) const {
std::stringstream ss;
ss << "<`" << class_->name()->chars() << "` instance>";
return ss.str();
}
bool InstanceObject::is_equal(BaseObject* other) const {
return false;
}
void InstanceObject::blacken(VM& vm) {
vm.gray_object(class_);
gray_table(vm, fields_);
}
InstanceObject* InstanceObject::create(VM& vm, ClassObject* klass) {
auto* o = new InstanceObject(klass);
vm.append_object(o);
return o;
}
BoundMethodObject::BoundMethodObject(const Value& receiver, ClosureObject* method)
: BaseObject(ObjType::BOUND_METHOD)
, receiver_(receiver)
, method_(method) {
}
BoundMethodObject::~BoundMethodObject(void) {
}
sz_t BoundMethodObject::size_bytes(void) const {
return sizeof(*this);
}
str_t BoundMethodObject::stringify(void) const {
std::stringstream ss;
ss << "<fn `" << method_->get_function()->name()->chars() << "`";
return ss.str();
}
bool BoundMethodObject::is_equal(BaseObject* other) const {
return false;
}
void BoundMethodObject::blacken(VM& vm) {
vm.gray_value(receiver_);
vm.gray_object(method_);
}
BoundMethodObject* BoundMethodObject::create(
VM& vm, const Value& receiver, ClosureObject* method) {
auto* o = new BoundMethodObject(receiver, method);
vm.append_object(o);
return o;
}
}
<|endoftext|> |
<commit_before>#include "TestRegistry.h"
#include "Test.h"
using namespace std;
using namespace CppUnit;
std::vector<std::string> s_registry_names;
std::vector<Test*> s_registry_tests;
static TestRegistry* s_registry;
static bool instanciated=false;
TestRegistry&
TestRegistry::getRegistry ()
{
if(!instanciated)
s_registry=new TestRegistry();
return *s_registry;
}
void
TestRegistry::addTest(string name, Test *test)
{
s_registry_names.push_back (name);
s_registry_tests.push_back (test);
}
const vector<string>&
TestRegistry::getAllTestNames () const
{
return(s_registry_names);
}
const vector<Test*>&
TestRegistry::getAllTests() const
{
return(s_registry_tests);
}
vector<Test*>
TestRegistry::getTest (const string& testCase) const
{
vector<Test*> res;
vector<Test*>::iterator test_it;
vector<string>::iterator name_it;
for (test_it = s_registry_tests.begin (),
name_it = s_registry_names.begin ();
test_it != s_registry_tests.end ();
++test_it, ++name_it) {
if ((*name_it) == testCase) {
res.push_back((*test_it));
break;
}
}
return(res);
}
TestRegistry::~TestRegistry ()
{
for (vector<Test*>::iterator it = s_registry_tests.begin ();
it != s_registry_tests.end ();
++it)
delete *it;
}
TestRegistry::TestRegistry ()
{
}
<commit_msg>fixed registry initialized flag.<commit_after>#include "TestRegistry.h"
#include "Test.h"
using namespace std;
using namespace CppUnit;
std::vector<std::string> s_registry_names;
std::vector<Test*> s_registry_tests;
static TestRegistry* s_registry;
static bool instanciated=false;
TestRegistry&
TestRegistry::getRegistry ()
{
if(!instanciated) {
s_registry=new TestRegistry();
instanciated=true;
}
return *s_registry;
}
void
TestRegistry::addTest(string name, Test *test)
{
s_registry_names.push_back (name);
s_registry_tests.push_back (test);
}
const vector<string>&
TestRegistry::getAllTestNames () const
{
return(s_registry_names);
}
const vector<Test*>&
TestRegistry::getAllTests() const
{
return(s_registry_tests);
}
vector<Test*>
TestRegistry::getTest (const string& testCase) const
{
vector<Test*> res;
vector<Test*>::iterator test_it;
vector<string>::iterator name_it;
for (test_it = s_registry_tests.begin (),
name_it = s_registry_names.begin ();
test_it != s_registry_tests.end ();
++test_it, ++name_it) {
if ((*name_it) == testCase) {
res.push_back((*test_it));
break;
}
}
return(res);
}
TestRegistry::~TestRegistry ()
{
for (vector<Test*>::iterator it = s_registry_tests.begin ();
it != s_registry_tests.end ();
++it)
delete *it;
}
TestRegistry::TestRegistry ()
{
}
<|endoftext|> |
<commit_before>#include "ifnet.h"
#include "connection.h"
#include "net.h"
#include "connectionmgr.h"
FxSession::FxSession()
{
m_poConnection = NULL;
//m_pDataHeader = NULL;
}
FxSession::~FxSession()
{
if (m_poConnection)
{
m_poConnection->SetSession(NULL);
FxConnectionMgr::Instance()->Release(m_poConnection);
m_poConnection = NULL;
}
//if (m_pDataHeader)
//{
// delete m_pDataHeader;
// m_pDataHeader = NULL;
//}
}
bool FxSession::Send(const char* pBuf,unsigned int dwLen)
{
if (!m_poConnection)
{
LogExe(LogLv_Error, "m_poConnection == NULL");
return false;
}
if (m_poConnection->IsConnected())
{
return m_poConnection->Send(pBuf, dwLen);
}
LogExe(LogLv_Error, "connection : %p, IsConnected() : %d", m_poConnection, (int)m_poConnection->IsConnected());
return false;
}
void FxSession::Close(void)
{
if (m_poConnection && m_poConnection->IsConnected())
{
m_poConnection->Close();
}
}
void FxSession::Init(FxConnection* poConnection)
{
m_poConnection = poConnection;
Init();
}
bool FxSession::SetSessionOpt(ESessionOpt eOpt, bool bSetting)
{
if (NULL == m_poConnection)
{
return false;
}
return m_poConnection->SetConnectionOpt(eOpt, bSetting);
}
bool FxSession::IsConnected(void)
{
if (NULL == m_poConnection)
{
return false;
}
return m_poConnection->IsConnected();
}
bool FxSession::IsConnecting(void)
{
if (NULL == m_poConnection)
{
return false;
}
return m_poConnection->IsConnecting();
}
SOCKET FxSession::Reconnect(void)
{
if (NULL == m_poConnection)
{
return INVALID_SOCKET;
}
return m_poConnection->Reconnect();
}
unsigned int FxSession::GetRemoteIP()
{
if (NULL != m_poConnection)
{
return m_poConnection->GetRemoteIP();
}
return 0;
}
const char* FxSession::GetRemoteIPStr()
{
if (NULL != m_poConnection)
{
return m_poConnection->GetRemoteIPStr();
}
return "NoIP";
}
unsigned int FxSession::GetRemotePort()
{
if (NULL != m_poConnection)
{
return m_poConnection->GetRemotePort();
}
return 0;
}
FxConnection* FxSession::GetConnection(void)
{
return m_poConnection;
}
bool FxSession::OnDestroy()
{
// connection release
if (m_poConnection)
{
m_poConnection->SetSession(NULL);
FxConnectionMgr::Instance()->Release(m_poConnection);
m_poConnection = NULL;
}
// if (m_pDataHeader)
// {
// delete m_pDataHeader;
// m_pDataHeader = NULL;
// }
return true;
}
//void FxSession::SetDataHeader(IFxDataHeader* pDataHeader)
//{
// m_pDataHeader = pDataHeader;
//}
IFxNet* FxNetGetModule()
{
if(NULL == FxNetModule::Instance())
{
#ifdef WIN32
WSADATA data;
int nErr = WSAStartup(MAKEWORD(2, 2), &data);
if (nErr != 0)
{
LogExe(LogLv_Error, "WSAStartup failed error no : %d", nErr);
}
#endif
if(false == FxNetModule::CreateInstance())
return NULL;
if(false == FxNetModule::Instance()->Init())
{
LogExe(LogLv_Error, "%s", "SDNetGetModule, Init CSDNetWin failed");
FxNetModule::DestroyInstance();
return NULL;
}
}
return FxNetModule::Instance();
}
int IFxDataHeader::ParsePacket(const char* pBuf, unsigned int dwLen)
{
if (dwLen < GetHeaderLength())
{
return 0;
}
int iPkgLen = __CheckPkgHeader(pBuf);
return iPkgLen;
}
<commit_msg>加入日志<commit_after>#include "ifnet.h"
#include "connection.h"
#include "net.h"
#include "connectionmgr.h"
FxSession::FxSession()
{
m_poConnection = NULL;
//m_pDataHeader = NULL;
}
FxSession::~FxSession()
{
if (m_poConnection)
{
m_poConnection->SetSession(NULL);
FxConnectionMgr::Instance()->Release(m_poConnection);
m_poConnection = NULL;
}
//if (m_pDataHeader)
//{
// delete m_pDataHeader;
// m_pDataHeader = NULL;
//}
}
bool FxSession::Send(const char* pBuf,unsigned int dwLen)
{
if (!m_poConnection)
{
LogExe(LogLv_Error, "m_poConnection == NULL");
return false;
}
if (m_poConnection->IsConnected())
{
return m_poConnection->Send(pBuf, dwLen);
}
LogExe(LogLv_Error, "connection : %p, id : %d, IsConnected() : %d", m_poConnection, m_poConnection->GetID, (int)m_poConnection->IsConnected());
return false;
}
void FxSession::Close(void)
{
if (m_poConnection && m_poConnection->IsConnected())
{
m_poConnection->Close();
}
}
void FxSession::Init(FxConnection* poConnection)
{
m_poConnection = poConnection;
Init();
}
bool FxSession::SetSessionOpt(ESessionOpt eOpt, bool bSetting)
{
if (NULL == m_poConnection)
{
return false;
}
return m_poConnection->SetConnectionOpt(eOpt, bSetting);
}
bool FxSession::IsConnected(void)
{
if (NULL == m_poConnection)
{
return false;
}
return m_poConnection->IsConnected();
}
bool FxSession::IsConnecting(void)
{
if (NULL == m_poConnection)
{
return false;
}
return m_poConnection->IsConnecting();
}
SOCKET FxSession::Reconnect(void)
{
if (NULL == m_poConnection)
{
return INVALID_SOCKET;
}
return m_poConnection->Reconnect();
}
unsigned int FxSession::GetRemoteIP()
{
if (NULL != m_poConnection)
{
return m_poConnection->GetRemoteIP();
}
return 0;
}
const char* FxSession::GetRemoteIPStr()
{
if (NULL != m_poConnection)
{
return m_poConnection->GetRemoteIPStr();
}
return "NoIP";
}
unsigned int FxSession::GetRemotePort()
{
if (NULL != m_poConnection)
{
return m_poConnection->GetRemotePort();
}
return 0;
}
FxConnection* FxSession::GetConnection(void)
{
return m_poConnection;
}
bool FxSession::OnDestroy()
{
// connection release
if (m_poConnection)
{
m_poConnection->SetSession(NULL);
FxConnectionMgr::Instance()->Release(m_poConnection);
m_poConnection = NULL;
}
// if (m_pDataHeader)
// {
// delete m_pDataHeader;
// m_pDataHeader = NULL;
// }
return true;
}
//void FxSession::SetDataHeader(IFxDataHeader* pDataHeader)
//{
// m_pDataHeader = pDataHeader;
//}
IFxNet* FxNetGetModule()
{
if(NULL == FxNetModule::Instance())
{
#ifdef WIN32
WSADATA data;
int nErr = WSAStartup(MAKEWORD(2, 2), &data);
if (nErr != 0)
{
LogExe(LogLv_Error, "WSAStartup failed error no : %d", nErr);
}
#endif
if(false == FxNetModule::CreateInstance())
return NULL;
if(false == FxNetModule::Instance()->Init())
{
LogExe(LogLv_Error, "%s", "SDNetGetModule, Init CSDNetWin failed");
FxNetModule::DestroyInstance();
return NULL;
}
}
return FxNetModule::Instance();
}
int IFxDataHeader::ParsePacket(const char* pBuf, unsigned int dwLen)
{
if (dwLen < GetHeaderLength())
{
return 0;
}
int iPkgLen = __CheckPkgHeader(pBuf);
return iPkgLen;
}
<|endoftext|> |
<commit_before>#include "Hotkeys.h"
#include <CommCtrl.h>
#include "../3RVX/HotkeyInfo.h"
#include "../3RVX/HotkeyManager.h"
#include "../3RVX/Logger.h"
#include "../3RVX/Settings.h"
#include "../3RVX/SkinInfo.h"
#include "resource.h"
void Hotkeys::Initialize() {
using std::placeholders::_1;
INIT_CONTROL(LST_KEYS, ListView, _keyList);
_keyList.OnItemChange = std::bind(&Hotkeys::OnKeyListItemChange, this, _1);
INIT_CONTROL(BTN_ADD, Button, _add);
INIT_CONTROL(BTN_REMOVE, Button, _remove);
INIT_CONTROL(BTN_KEYS, Button, _keys);
INIT_CONTROL(CMB_ACTION, ComboBox, _action);
}
void Hotkeys::LoadSettings() {
Settings *settings = Settings::Instance();
/* Make highlighted items span the entire row in the list view */
_keyList.AddListExStyle(LVS_EX_FULLROWSELECT);
RECT dims = _keyList.Dimensions();
int width = dims.right - dims.left;
_keyList.AddColumn(hotkeysColumnStr, (int) (width * .485));
_keyList.AddColumn(actionColumnStr, (int) (width * .445));
for (std::wstring action : HotkeyInfo::ActionNames) {
_action.AddItem(action);
}
std::unordered_map<int, HotkeyInfo> hotkeys = settings->Hotkeys();
for (auto it = hotkeys.begin(); it != hotkeys.end(); ++it) {
_keyInfo.push_back(it->second);
}
for (unsigned int i = 0; i < _keyInfo.size(); ++i) {
HotkeyInfo hki = _keyInfo[i];
std::wstring hkStr = HotkeyManager::HotkeysToString(hki.keyCombination);
int idx = _keyList.AddItem(hkStr);
_keyList.ItemText(idx, 1, HotkeyInfo::ActionNames[hki.action]);
}
_keyList.Selection(0);
}
void Hotkeys::SaveSettings() {
if (_hWnd == NULL) {
return;
}
CLOG(L"Saving: Hotkeys");
Settings *settings = Settings::Instance();
}
bool Hotkeys::OnAddButtonClick() {
int items = _keyList.Size();
for (int i = 0; i < items; ++i) {
if (_keyList.ItemText(i, 0) == L"" && _keyList.ItemText(i, 1) == L"") {
/* We found a blank item already in the list */
_keyList.Selection(i);
return true;
}
}
HotkeyInfo hi;
_keyInfo.push_back(hi);
int idx = _keyList.InsertItem(items, L"");
_keyList.ItemText(idx, 1, L"");
_keyList.Selection(idx);
return true;
}
bool Hotkeys::OnRemoveButtonClick() {
int sel = _keyList.Selection();
CLOG(L"Removing: %d", sel);
_keyInfo.erase(_keyInfo.begin() + sel);
_keyList.RemoveItem(sel);
/* Select the item closest to the previous selection: */
_keyList.Selection(sel);
return true;
}
void Hotkeys::OnKeyListItemChange(NMLISTVIEW *lv) {
if (lv->uChanged & LVIF_STATE) {
if (lv->uNewState & LVIS_SELECTED) {
OnKeyListSelectionChange(lv->iItem);
}
}
}
void Hotkeys::OnKeyListSelectionChange(int index) {
HotkeyInfo current = _keyInfo[index];
CLOG(L"Selecting key combination %d:", index);
QCLOG(L"%s", current.ToString().c_str());
}<commit_msg>Link up button event handlers<commit_after>#include "Hotkeys.h"
#include <CommCtrl.h>
#include "../3RVX/HotkeyInfo.h"
#include "../3RVX/HotkeyManager.h"
#include "../3RVX/Logger.h"
#include "../3RVX/Settings.h"
#include "../3RVX/SkinInfo.h"
#include "resource.h"
void Hotkeys::Initialize() {
using std::placeholders::_1;
INIT_CONTROL(LST_KEYS, ListView, _keyList);
_keyList.OnItemChange = std::bind(&Hotkeys::OnKeyListItemChange, this, _1);
INIT_CONTROL(BTN_ADD, Button, _add);
_add.OnClick = std::bind(&Hotkeys::OnAddButtonClick, this);
INIT_CONTROL(BTN_REMOVE, Button, _remove);
_remove.OnClick = std::bind(&Hotkeys::OnRemoveButtonClick, this);
INIT_CONTROL(BTN_KEYS, Button, _keys);
INIT_CONTROL(CMB_ACTION, ComboBox, _action);
}
void Hotkeys::LoadSettings() {
Settings *settings = Settings::Instance();
/* Make highlighted items span the entire row in the list view */
_keyList.AddListExStyle(LVS_EX_FULLROWSELECT);
RECT dims = _keyList.Dimensions();
int width = dims.right - dims.left;
_keyList.AddColumn(hotkeysColumnStr, (int) (width * .485));
_keyList.AddColumn(actionColumnStr, (int) (width * .445));
for (std::wstring action : HotkeyInfo::ActionNames) {
_action.AddItem(action);
}
std::unordered_map<int, HotkeyInfo> hotkeys = settings->Hotkeys();
for (auto it = hotkeys.begin(); it != hotkeys.end(); ++it) {
_keyInfo.push_back(it->second);
}
for (unsigned int i = 0; i < _keyInfo.size(); ++i) {
HotkeyInfo hki = _keyInfo[i];
std::wstring hkStr = HotkeyManager::HotkeysToString(hki.keyCombination);
int idx = _keyList.AddItem(hkStr);
_keyList.ItemText(idx, 1, HotkeyInfo::ActionNames[hki.action]);
}
_keyList.Selection(0);
}
void Hotkeys::SaveSettings() {
if (_hWnd == NULL) {
return;
}
CLOG(L"Saving: Hotkeys");
Settings *settings = Settings::Instance();
}
bool Hotkeys::OnAddButtonClick() {
int items = _keyList.Size();
for (int i = 0; i < items; ++i) {
if (_keyList.ItemText(i, 0) == L"" && _keyList.ItemText(i, 1) == L"") {
/* We found a blank item already in the list */
_keyList.Selection(i);
return true;
}
}
HotkeyInfo hi;
_keyInfo.push_back(hi);
int idx = _keyList.InsertItem(items, L"");
_keyList.ItemText(idx, 1, L"");
_keyList.Selection(idx);
return true;
}
bool Hotkeys::OnRemoveButtonClick() {
int sel = _keyList.Selection();
CLOG(L"Removing: %d", sel);
_keyInfo.erase(_keyInfo.begin() + sel);
_keyList.RemoveItem(sel);
/* Select the item closest to the previous selection: */
_keyList.Selection(sel);
return true;
}
void Hotkeys::OnKeyListItemChange(NMLISTVIEW *lv) {
if (lv->uChanged & LVIF_STATE) {
if (lv->uNewState & LVIS_SELECTED) {
OnKeyListSelectionChange(lv->iItem);
}
}
}
void Hotkeys::OnKeyListSelectionChange(int index) {
HotkeyInfo current = _keyInfo[index];
CLOG(L"Selecting key combination %d:", index);
QCLOG(L"%s", current.ToString().c_str());
}<|endoftext|> |
<commit_before>/****************************************************************************
**
** Copyright (C) 2009 Nokia Corporation and/or its subsidiary(-ies).
** Contact: Qt Software Information (qt-info@nokia.com)
**
** This file is part of the QtDeclarative module of the Qt Toolkit.
**
** $QT_BEGIN_LICENSE:LGPL$
** No Commercial Usage
** This file contains pre-release code and may not be distributed.
** You may use this file in accordance with the terms and conditions
** contained in the either Technology Preview License Agreement or the
** Beta Release License Agreement.
**
** GNU Lesser General Public License Usage
** Alternatively, this file may be used under the terms of the GNU Lesser
** General Public License version 2.1 as published by the Free Software
** Foundation and appearing in the file LICENSE.LGPL included in the
** packaging of this file. Please review the following information to
** ensure the GNU Lesser General Public License version 2.1 requirements
** will be met: http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html.
**
** In addition, as a special exception, Nokia gives you certain
** additional rights. These rights are described in the Nokia Qt LGPL
** Exception version 1.0, included in the file LGPL_EXCEPTION.txt in this
** package.
**
** GNU General Public License Usage
** Alternatively, this file may be used under the terms of the GNU
** General Public License version 3.0 as published by the Free Software
** Foundation and appearing in the file LICENSE.GPL included in the
** packaging of this file. Please review the following information to
** ensure the GNU General Public License version 3.0 requirements will be
** met: http://www.gnu.org/copyleft/gpl.html.
**
** If you are unsure which license is appropriate for your use, please
** contact the sales department at qt-sales@nokia.com.
** $QT_END_LICENSE$
**
****************************************************************************/
#include "qmlobjectscriptclass_p.h"
#include <private/qmlengine_p.h>
#include <private/qguard_p.h>
#include <private/qmlcontext_p.h>
#include <private/qmldeclarativedata_p.h>
#include <private/qmltypenamescriptclass_p.h>
#include <QtDeclarative/qmlbinding.h>
QT_BEGIN_NAMESPACE
struct ObjectData : public QScriptDeclarativeClass::Object {
ObjectData(QObject *o) : object(o) {}
QGuard<QObject> object;
};
/*
The QmlObjectScriptClass handles property access for QObjects
via QtScript. It is also used to provide a more useful API in
QtScript for QML.
*/
QmlObjectScriptClass::QmlObjectScriptClass(QmlEngine *bindEngine)
: QScriptDeclarativeClass(QmlEnginePrivate::getScriptEngine(bindEngine)), lastData(0),
engine(bindEngine)
{
engine = bindEngine;
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(bindEngine);
m_destroy = scriptEngine->newFunction(destroy);
m_destroyId = createPersistentIdentifier(QLatin1String("destroy"));
m_toString = scriptEngine->newFunction(tostring);
m_toStringId = createPersistentIdentifier(QLatin1String("toString"));
}
QmlObjectScriptClass::~QmlObjectScriptClass()
{
}
QScriptValue QmlObjectScriptClass::newQObject(QObject *object)
{
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(engine);
if (!object)
return newObject(scriptEngine, this, new ObjectData(object));
QmlDeclarativeData *ddata = QmlDeclarativeData::get(object, true);
if (!ddata->scriptValue.isValid()) {
ddata->scriptValue = newObject(scriptEngine, this, new ObjectData(object));
return ddata->scriptValue;
} else if (ddata->scriptValue.engine() == QmlEnginePrivate::getScriptEngine(engine)) {
return ddata->scriptValue;
} else {
return newObject(scriptEngine, this, new ObjectData(object));
}
}
QObject *QmlObjectScriptClass::toQObject(const QScriptValue &value) const
{
return value.toQObject();
}
QScriptClass::QueryFlags
QmlObjectScriptClass::queryProperty(Object *object, const Identifier &name,
QScriptClass::QueryFlags flags)
{
return queryProperty(toQObject(object), name, flags, 0);
}
QScriptClass::QueryFlags
QmlObjectScriptClass::queryProperty(QObject *obj, const Identifier &name,
QScriptClass::QueryFlags flags, QmlContext *evalContext)
{
Q_UNUSED(flags);
lastData = 0;
lastTNData = 0;
if (name == m_destroyId.identifier ||
name == m_toStringId.identifier)
return QScriptClass::HandlesReadAccess;
if (!obj)
return 0;
QmlEnginePrivate *enginePrivate = QmlEnginePrivate::get(engine);
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(engine);
QmlPropertyCache *cache = 0;
QmlDeclarativeData *ddata = QmlDeclarativeData::get(obj);
if (ddata)
cache = ddata->propertyCache;
if (!cache) {
cache = enginePrivate->cache(obj);
if (ddata) { cache->addref(); ddata->propertyCache = cache; }
}
if (cache) {
lastData = cache->property(name);
} else {
local = QmlPropertyCache::create(obj->metaObject(), toString(name));
if (local.isValid())
lastData = &local;
}
if (lastData) {
QScriptClass::QueryFlags rv = QScriptClass::HandlesReadAccess;
if (lastData->flags & QmlPropertyCache::Data::IsWritable)
rv |= QScriptClass::HandlesWriteAccess;
return rv;
}
if (!evalContext && context) {
// Global object, QScriptContext activation object, QmlContext object
QScriptValue scopeNode = scopeChainValue(context, 3);
Q_ASSERT(scopeNode.isValid());
Q_ASSERT(scriptClass(scopeNode) == enginePrivate->contextClass);
evalContext = enginePrivate->contextClass->contextFromValue(scopeNode);
}
if (evalContext) {
QmlContextPrivate *cp = QmlContextPrivate::get(evalContext);
if (cp->imports) {
QmlTypeNameCache::Data *data = cp->imports->data(name);
if (data) {
lastTNData = data;
return QScriptClass::HandlesReadAccess;
}
}
}
return 0;
}
QScriptValue QmlObjectScriptClass::property(Object *object, const Identifier &name)
{
return property(toQObject(object), name);
}
QScriptValue QmlObjectScriptClass::property(QObject *obj, const Identifier &name)
{
if (name == m_destroyId.identifier)
return m_destroy;
else if (name == m_toStringId.identifier)
return m_toString;
Q_ASSERT(lastData);
Q_ASSERT(obj);
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(engine);
QmlEnginePrivate *enginePriv = QmlEnginePrivate::get(engine);
if (lastTNData) {
if (lastTNData->type)
return enginePriv->typeNameClass->newObject(obj, lastTNData->type);
else
return enginePriv->typeNameClass->newObject(obj, lastTNData->typeNamespace);
} else if (lastData->flags & QmlPropertyCache::Data::IsFunction) {
// ### Optimize
QScriptValue sobj = scriptEngine->newQObject(obj);
return sobj.property(toString(name));
} else {
if (!(lastData->flags & QmlPropertyCache::Data::IsConstant)) {
enginePriv->capturedProperties <<
QmlEnginePrivate::CapturedProperty(obj, lastData->coreIndex, lastData->notifyIndex);
}
if ((uint)lastData->propType < QVariant::UserType) {
QmlValueType *valueType = enginePriv->valueTypes[lastData->propType];
if (valueType)
return enginePriv->valueTypeClass->newObject(obj, lastData->coreIndex, valueType);
}
QVariant var = obj->metaObject()->property(lastData->coreIndex).read(obj);
if (lastData->flags & QmlPropertyCache::Data::IsQObjectDerived) {
QObject *rv = *(QObject **)var.constData();
return newQObject(rv);
} else {
return enginePriv->scriptValueFromVariant(var);
}
}
}
void QmlObjectScriptClass::setProperty(Object *object,
const Identifier &name,
const QScriptValue &value)
{
return setProperty(toQObject(object), name, value);
}
void QmlObjectScriptClass::setProperty(QObject *obj,
const Identifier &name,
const QScriptValue &value)
{
Q_UNUSED(name);
Q_ASSERT(obj);
Q_ASSERT(lastData);
QmlEnginePrivate *enginePriv = QmlEnginePrivate::get(engine);
// ### Can well known types be optimized?
QVariant v = QmlScriptClass::toVariant(engine, value);
delete QmlMetaPropertyPrivate::setBinding(obj, *lastData, 0);
QmlMetaPropertyPrivate::write(obj, *lastData, v, enginePriv->currentExpression->context());
}
QObject *QmlObjectScriptClass::toQObject(Object *object, bool *ok)
{
if (ok) *ok = true;
ObjectData *data = (ObjectData*)object;
return data->object.data();
}
QScriptValue QmlObjectScriptClass::tostring(QScriptContext *context, QScriptEngine *)
{
QObject* obj = context->thisObject().toQObject();
QString ret;
if(obj){
QString objectName = obj->objectName();
ret += QLatin1String(obj->metaObject()->className());
ret += QLatin1String("(0x");
ret += QString::number((quintptr)obj,16);
if (!objectName.isEmpty()) {
ret += QLatin1String(", \"");
ret += objectName;
ret += QLatin1String("\"");
}
ret += QLatin1String(")");
}else{
ret += QLatin1String("null");
}
return QScriptValue(ret);
}
QScriptValue QmlObjectScriptClass::destroy(QScriptContext *context, QScriptEngine *engine)
{
QObject* obj = context->thisObject().toQObject();
if(obj){
int delay = 0;
if(context->argumentCount() > 0)
delay = context->argument(0).toInt32();
obj->deleteLater();
//### Should this be delayed as well?
context->thisObject().setData(QScriptValue(engine, 0));
}
return engine->nullValue();
}
QT_END_NAMESPACE
<commit_msg>Add Object.destroy(int delay) parameter<commit_after>/****************************************************************************
**
** Copyright (C) 2009 Nokia Corporation and/or its subsidiary(-ies).
** Contact: Qt Software Information (qt-info@nokia.com)
**
** This file is part of the QtDeclarative module of the Qt Toolkit.
**
** $QT_BEGIN_LICENSE:LGPL$
** No Commercial Usage
** This file contains pre-release code and may not be distributed.
** You may use this file in accordance with the terms and conditions
** contained in the either Technology Preview License Agreement or the
** Beta Release License Agreement.
**
** GNU Lesser General Public License Usage
** Alternatively, this file may be used under the terms of the GNU Lesser
** General Public License version 2.1 as published by the Free Software
** Foundation and appearing in the file LICENSE.LGPL included in the
** packaging of this file. Please review the following information to
** ensure the GNU Lesser General Public License version 2.1 requirements
** will be met: http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html.
**
** In addition, as a special exception, Nokia gives you certain
** additional rights. These rights are described in the Nokia Qt LGPL
** Exception version 1.0, included in the file LGPL_EXCEPTION.txt in this
** package.
**
** GNU General Public License Usage
** Alternatively, this file may be used under the terms of the GNU
** General Public License version 3.0 as published by the Free Software
** Foundation and appearing in the file LICENSE.GPL included in the
** packaging of this file. Please review the following information to
** ensure the GNU General Public License version 3.0 requirements will be
** met: http://www.gnu.org/copyleft/gpl.html.
**
** If you are unsure which license is appropriate for your use, please
** contact the sales department at qt-sales@nokia.com.
** $QT_END_LICENSE$
**
****************************************************************************/
#include "qmlobjectscriptclass_p.h"
#include <private/qmlengine_p.h>
#include <private/qguard_p.h>
#include <private/qmlcontext_p.h>
#include <private/qmldeclarativedata_p.h>
#include <private/qmltypenamescriptclass_p.h>
#include <QtDeclarative/qmlbinding.h>
#include <QtCore/qtimer.h>
QT_BEGIN_NAMESPACE
struct ObjectData : public QScriptDeclarativeClass::Object {
ObjectData(QObject *o) : object(o) {}
QGuard<QObject> object;
};
/*
The QmlObjectScriptClass handles property access for QObjects
via QtScript. It is also used to provide a more useful API in
QtScript for QML.
*/
QmlObjectScriptClass::QmlObjectScriptClass(QmlEngine *bindEngine)
: QScriptDeclarativeClass(QmlEnginePrivate::getScriptEngine(bindEngine)), lastData(0),
engine(bindEngine)
{
engine = bindEngine;
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(bindEngine);
m_destroy = scriptEngine->newFunction(destroy);
m_destroyId = createPersistentIdentifier(QLatin1String("destroy"));
m_toString = scriptEngine->newFunction(tostring);
m_toStringId = createPersistentIdentifier(QLatin1String("toString"));
}
QmlObjectScriptClass::~QmlObjectScriptClass()
{
}
QScriptValue QmlObjectScriptClass::newQObject(QObject *object)
{
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(engine);
if (!object)
return newObject(scriptEngine, this, new ObjectData(object));
QmlDeclarativeData *ddata = QmlDeclarativeData::get(object, true);
if (!ddata->scriptValue.isValid()) {
ddata->scriptValue = newObject(scriptEngine, this, new ObjectData(object));
return ddata->scriptValue;
} else if (ddata->scriptValue.engine() == QmlEnginePrivate::getScriptEngine(engine)) {
return ddata->scriptValue;
} else {
return newObject(scriptEngine, this, new ObjectData(object));
}
}
QObject *QmlObjectScriptClass::toQObject(const QScriptValue &value) const
{
return value.toQObject();
}
QScriptClass::QueryFlags
QmlObjectScriptClass::queryProperty(Object *object, const Identifier &name,
QScriptClass::QueryFlags flags)
{
return queryProperty(toQObject(object), name, flags, 0);
}
QScriptClass::QueryFlags
QmlObjectScriptClass::queryProperty(QObject *obj, const Identifier &name,
QScriptClass::QueryFlags flags, QmlContext *evalContext)
{
Q_UNUSED(flags);
lastData = 0;
lastTNData = 0;
if (name == m_destroyId.identifier ||
name == m_toStringId.identifier)
return QScriptClass::HandlesReadAccess;
if (!obj)
return 0;
QmlEnginePrivate *enginePrivate = QmlEnginePrivate::get(engine);
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(engine);
QmlPropertyCache *cache = 0;
QmlDeclarativeData *ddata = QmlDeclarativeData::get(obj);
if (ddata)
cache = ddata->propertyCache;
if (!cache) {
cache = enginePrivate->cache(obj);
if (ddata) { cache->addref(); ddata->propertyCache = cache; }
}
if (cache) {
lastData = cache->property(name);
} else {
local = QmlPropertyCache::create(obj->metaObject(), toString(name));
if (local.isValid())
lastData = &local;
}
if (lastData) {
QScriptClass::QueryFlags rv = QScriptClass::HandlesReadAccess;
if (lastData->flags & QmlPropertyCache::Data::IsWritable)
rv |= QScriptClass::HandlesWriteAccess;
return rv;
}
if (!evalContext && context) {
// Global object, QScriptContext activation object, QmlContext object
QScriptValue scopeNode = scopeChainValue(context, 3);
Q_ASSERT(scopeNode.isValid());
Q_ASSERT(scriptClass(scopeNode) == enginePrivate->contextClass);
evalContext = enginePrivate->contextClass->contextFromValue(scopeNode);
}
if (evalContext) {
QmlContextPrivate *cp = QmlContextPrivate::get(evalContext);
if (cp->imports) {
QmlTypeNameCache::Data *data = cp->imports->data(name);
if (data) {
lastTNData = data;
return QScriptClass::HandlesReadAccess;
}
}
}
return 0;
}
QScriptValue QmlObjectScriptClass::property(Object *object, const Identifier &name)
{
return property(toQObject(object), name);
}
QScriptValue QmlObjectScriptClass::property(QObject *obj, const Identifier &name)
{
if (name == m_destroyId.identifier)
return m_destroy;
else if (name == m_toStringId.identifier)
return m_toString;
Q_ASSERT(lastData);
Q_ASSERT(obj);
QScriptEngine *scriptEngine = QmlEnginePrivate::getScriptEngine(engine);
QmlEnginePrivate *enginePriv = QmlEnginePrivate::get(engine);
if (lastTNData) {
if (lastTNData->type)
return enginePriv->typeNameClass->newObject(obj, lastTNData->type);
else
return enginePriv->typeNameClass->newObject(obj, lastTNData->typeNamespace);
} else if (lastData->flags & QmlPropertyCache::Data::IsFunction) {
// ### Optimize
QScriptValue sobj = scriptEngine->newQObject(obj);
return sobj.property(toString(name));
} else {
if (!(lastData->flags & QmlPropertyCache::Data::IsConstant)) {
enginePriv->capturedProperties <<
QmlEnginePrivate::CapturedProperty(obj, lastData->coreIndex, lastData->notifyIndex);
}
if ((uint)lastData->propType < QVariant::UserType) {
QmlValueType *valueType = enginePriv->valueTypes[lastData->propType];
if (valueType)
return enginePriv->valueTypeClass->newObject(obj, lastData->coreIndex, valueType);
}
QVariant var = obj->metaObject()->property(lastData->coreIndex).read(obj);
if (lastData->flags & QmlPropertyCache::Data::IsQObjectDerived) {
QObject *rv = *(QObject **)var.constData();
return newQObject(rv);
} else {
return enginePriv->scriptValueFromVariant(var);
}
}
}
void QmlObjectScriptClass::setProperty(Object *object,
const Identifier &name,
const QScriptValue &value)
{
return setProperty(toQObject(object), name, value);
}
void QmlObjectScriptClass::setProperty(QObject *obj,
const Identifier &name,
const QScriptValue &value)
{
Q_UNUSED(name);
Q_ASSERT(obj);
Q_ASSERT(lastData);
QmlEnginePrivate *enginePriv = QmlEnginePrivate::get(engine);
// ### Can well known types be optimized?
QVariant v = QmlScriptClass::toVariant(engine, value);
delete QmlMetaPropertyPrivate::setBinding(obj, *lastData, 0);
QmlMetaPropertyPrivate::write(obj, *lastData, v, enginePriv->currentExpression->context());
}
QObject *QmlObjectScriptClass::toQObject(Object *object, bool *ok)
{
if (ok) *ok = true;
ObjectData *data = (ObjectData*)object;
return data->object.data();
}
QScriptValue QmlObjectScriptClass::tostring(QScriptContext *context, QScriptEngine *)
{
QObject* obj = context->thisObject().toQObject();
QString ret;
if(obj){
QString objectName = obj->objectName();
ret += QLatin1String(obj->metaObject()->className());
ret += QLatin1String("(0x");
ret += QString::number((quintptr)obj,16);
if (!objectName.isEmpty()) {
ret += QLatin1String(", \"");
ret += objectName;
ret += QLatin1String("\"");
}
ret += QLatin1String(")");
}else{
ret += QLatin1String("null");
}
return QScriptValue(ret);
}
QScriptValue QmlObjectScriptClass::destroy(QScriptContext *context, QScriptEngine *engine)
{
QObject* obj = context->thisObject().toQObject();
if(obj){
int delay = 0;
if(context->argumentCount() > 0)
delay = context->argument(0).toInt32();
if (delay > 0)
QTimer::singleShot(delay, obj, SLOT(deleteLater()));
else
obj->deleteLater();
}
return engine->nullValue();
}
QT_END_NAMESPACE
<|endoftext|> |
<commit_before>#include "stdafx.h"
#include "TDB_API.h"
#include "TDB_API_helper.h"
#include "kdb+.util/util.h"
#include "kdb+.util/K_ptr.h"
TDB_API K K_DECL TDB_codeTable(K h, K market) {
::THANDLE tdb = NULL;
std::string mkt;
try {
TDB::parseTdbHandle(h, tdb);
mkt = q::q2String(market);
}
catch (std::string const& error) {
return q::error2q(error);
}
typedef ::TDBDefine_Code tdb_result_type;
int codeCount = 0;
tdb_result_type* t = NULL;
::TDB_ERROR const result = static_cast<::TDB_ERROR>(::TDB_GetCodeTable(tdb, mkt.c_str(), &t, &codeCount));
TDB::Ptr<tdb_result_type> codes(t);
if (result != TDB_SUCCESS) {
return q::error2q(TDB::getError(result));
}
assert(codes);
assert(codeCount >= 0);
typedef Wind::accessor::SymbolAccessor<tdb_result_type, char[32]> SymbolAccessor;
typedef TDB::MarketIdAccessor<tdb_result_type> MarketIdAccessor;
typedef Wind::accessor::SymbolAccessor<tdb_result_type, char[32], Wind::encoder::GB18030_UTF8> CnNameAccessor;
typedef Wind::accessor::IntAccessor<tdb_result_type, G> TypeAccessor;
q::K_ptr data(ktn(0, 8));
//ô(AG1312.SHF)
kK(data.get())[0] = SymbolAccessor(&tdb_result_type::chWindCode).extract(codes.get(), codeCount);
//(ag1312)
kK(data.get())[1] = SymbolAccessor(&tdb_result_type::chCode).extract(codes.get(), codeCount);
//г(SHF
kK(data.get())[2] = MarketIdAccessor(&tdb_result_type::chMarket).extract(codes.get(), codeCount);
//֤ȯ
kK(data.get())[3] = CnNameAccessor(&tdb_result_type::chCNName).extract(codes.get(), codeCount);
//֤ȯӢ
kK(data.get())[4] = SymbolAccessor(&tdb_result_type::chENName).extract(codes.get(), codeCount);
//֤ȯ
kK(data.get())[5] = TypeAccessor(&tdb_result_type::nType).extract(codes.get(), codeCount);
//Market level
kK(data.get())[6] = TDB::MarketInfoAccessor<tdb_result_type, 1, H>
(&tdb_result_type::chMarket).extract(codes.get(), codeCount);
//Data source ID
kK(data.get())[7] = TDB::MarketInfoAccessor<tdb_result_type, 2, H>
(&tdb_result_type::chMarket).extract(codes.get(), codeCount);
return data.release();
}
TDB_API K K_DECL TDB_codeInfo(K h, K windCode, K market) {
::THANDLE tdb = NULL;
std::string code, mkt;
try {
TDB::parseTdbHandle(h, tdb);
code = q::q2String(windCode);
mkt = TDB::getMarketId(tdb, q::q2String(market));
}
catch (std::string const& error) {
return q::error2q(error);
}
typedef ::TDBDefine_Code tdb_result_type;
tdb_result_type const* info = ::TDB_GetCodeInfo(tdb, code.c_str(), mkt.c_str());
if (info == NULL) {
return q::error2q(TDB::getError(TDB_NETWORK_ERROR));
}
q::K_ptr data(ktn(0, 8));
std::vector<std::string> mktTokens = util::split(info->chMarket, '-');
kK(data.get())[0] = ks(const_cast<S>(info->chWindCode));
kK(data.get())[1] = ks(const_cast<S>(info->chCode));
kK(data.get())[2] = ks((mktTokens.size() <= 0) ? q::type_traits<S>::NULL_VAL : const_cast<S>(mktTokens[0].c_str()));
kK(data.get())[3] = ks(const_cast<S>(Wind::encoder::GB18030_UTF8::encode(info->chCNName).c_str()));
kK(data.get())[4] = ks(const_cast<S>(info->chENName));
kK(data.get())[5] = kg(info->nType);
long const level = (mktTokens.size() <= 1) ? q::type_traits<H>::NULL_VAL : std::strtol(mktTokens[1].c_str(), NULL, 10);
kK(data.get())[6] = kh(static_cast<H>(level));
long const src = (mktTokens.size() <= 1) ? q::type_traits<H>::NULL_VAL : std::strtol(mktTokens[1].c_str(), NULL, 10);
kK(data.get())[7] = kh(static_cast<H>(src));
return data.release();
}<commit_msg>minor code clean-up<commit_after>#include "stdafx.h"
#include "TDB_API.h"
#include "TDB_API_helper.h"
#include "kdb+.util/util.h"
#include "kdb+.util/K_ptr.h"
TDB_API K K_DECL TDB_codeTable(K h, K market) {
::THANDLE tdb = NULL;
std::string mkt;
try {
TDB::parseTdbHandle(h, tdb);
mkt = q::q2String(market);
}
catch (std::string const& error) {
return q::error2q(error);
}
typedef ::TDBDefine_Code tdb_result_type;
int codeCount = 0;
tdb_result_type* t = NULL;
::TDB_ERROR const result = static_cast<::TDB_ERROR>(::TDB_GetCodeTable(tdb, mkt.c_str(), &t, &codeCount));
TDB::Ptr<tdb_result_type> codes(t);
if (result != TDB_SUCCESS) {
return q::error2q(TDB::getError(result));
}
assert(codes);
assert(codeCount >= 0);
typedef Wind::accessor::SymbolAccessor<tdb_result_type, char[32]> SymbolAccessor;
typedef TDB::MarketIdAccessor<tdb_result_type> MarketIdAccessor;
typedef TDB::MarketInfoAccessor<tdb_result_type, 1, H> MarketLevelAccessor;
typedef TDB::MarketInfoAccessor<tdb_result_type, 2, H> DataSourceAccessor;
typedef Wind::accessor::SymbolAccessor<tdb_result_type, char[32], Wind::encoder::GB18030_UTF8> CnNameAccessor;
typedef Wind::accessor::IntAccessor<tdb_result_type, G> TypeAccessor;
q::K_ptr data(ktn(0, 8));
//ô(AG1312.SHF)
kK(data.get())[0] = SymbolAccessor(&tdb_result_type::chWindCode).extract(codes.get(), codeCount);
//(ag1312)
kK(data.get())[1] = SymbolAccessor(&tdb_result_type::chCode).extract(codes.get(), codeCount);
//г(SHF
kK(data.get())[2] = MarketIdAccessor(&tdb_result_type::chMarket).extract(codes.get(), codeCount);
//֤ȯ
kK(data.get())[3] = CnNameAccessor(&tdb_result_type::chCNName).extract(codes.get(), codeCount);
//֤ȯӢ
kK(data.get())[4] = SymbolAccessor(&tdb_result_type::chENName).extract(codes.get(), codeCount);
//֤ȯ
kK(data.get())[5] = TypeAccessor(&tdb_result_type::nType).extract(codes.get(), codeCount);
//Market level
kK(data.get())[6] = MarketLevelAccessor(&tdb_result_type::chMarket).extract(codes.get(), codeCount);
//Data source ID
kK(data.get())[7] = DataSourceAccessor(&tdb_result_type::chMarket).extract(codes.get(), codeCount);
return data.release();
}
TDB_API K K_DECL TDB_codeInfo(K h, K windCode, K market) {
::THANDLE tdb = NULL;
std::string code, mkt;
try {
TDB::parseTdbHandle(h, tdb);
code = q::q2String(windCode);
mkt = TDB::getMarketId(tdb, q::q2String(market));
}
catch (std::string const& error) {
return q::error2q(error);
}
typedef ::TDBDefine_Code tdb_result_type;
tdb_result_type const* info = ::TDB_GetCodeInfo(tdb, code.c_str(), mkt.c_str());
if (info == NULL) {
return q::error2q(TDB::getError(TDB_NETWORK_ERROR));
}
q::K_ptr data(ktn(0, 8));
std::vector<std::string> mktTokens = util::split(info->chMarket, '-');
kK(data.get())[0] = ks(const_cast<S>(info->chWindCode));
kK(data.get())[1] = ks(const_cast<S>(info->chCode));
kK(data.get())[2] = ks((mktTokens.size() <= 0) ? q::type_traits<S>::NULL_VAL : const_cast<S>(mktTokens[0].c_str()));
kK(data.get())[3] = ks(const_cast<S>(Wind::encoder::GB18030_UTF8::encode(info->chCNName).c_str()));
kK(data.get())[4] = ks(const_cast<S>(info->chENName));
kK(data.get())[5] = kg(info->nType);
long const level = (mktTokens.size() <= 1) ? q::type_traits<H>::NULL_VAL : std::strtol(mktTokens[1].c_str(), NULL, 10);
kK(data.get())[6] = kh(static_cast<H>(level));
long const src = (mktTokens.size() <= 1) ? q::type_traits<H>::NULL_VAL : std::strtol(mktTokens[1].c_str(), NULL, 10);
kK(data.get())[7] = kh(static_cast<H>(src));
return data.release();
}<|endoftext|> |
<commit_before>/**************************************************************************
* Copyright(c) 1998-1999, ALICE Experiment at CERN, All rights reserved. *
* *
* Author: The ALICE Off-line Project. *
* Contributors are mentioned in the code where appropriate. *
* *
* Permission to use, copy, modify and distribute this software and its *
* documentation strictly for non-commercial purposes is hereby granted *
* without fee, provided that the above copyright notice appears in all *
* copies and that both the copyright notice and this permission notice *
* appear in the supporting documentation. The authors make no claims *
* about the suitability of this software for any purpose. It is *
* provided "as is" without express or implied warranty. *
**************************************************************************/
//-----------------------------------------------------------------//
// //
// Implementation of the TOF PID class //
// Origin: Iouri Belikov, CERN, Jouri.Belikov@cern.ch //
// //
//-----------------------------------------------------------------//
#include "TMath.h"
#include "AliLog.h"
#include "AliESDtrack.h"
#include "AliESDEvent.h"
#include "AliTOFpidESD.h"
ClassImp(AliTOFpidESD)
//_________________________________________________________________________
AliTOFpidESD::AliTOFpidESD():
fSigma(0),
fRange(0),
fPmax(0) // zero at 0.5 GeV/c for pp
{
}
//_________________________________________________________________________
AliTOFpidESD::AliTOFpidESD(Double_t *param):
fSigma(param[0]),
fRange(param[1]),
fPmax(0) // zero at 0.5 GeV/c for pp
{
//
// The main constructor
//
//
//fPmax=TMath::Exp(-0.5*3*3)/fSigma; // ~3 sigma at 0.5 GeV/c for PbPb
}
Double_t
AliTOFpidESD::GetMismatchProbability(Double_t p, Double_t mass) const {
//
// Returns the probability of mismatching
// assuming 1/(p*beta)^2 scaling
//
const Double_t m=0.5; // "reference" momentum (GeV/c)
Double_t ref2=m*m*m*m/(m*m + mass*mass);// "reference" (p*beta)^2
Double_t p2beta2=p*p*p*p/(p*p + mass*mass);
return fPmax*ref2/p2beta2;
}
//_________________________________________________________________________
Int_t AliTOFpidESD::MakePID(AliESDEvent *event, Double_t timeZero)
{
//
// This function calculates the "detector response" PID probabilities
// Just for a bare hint...
AliDebug(1,Form("TOF PID Parameters: Sigma (ps)= %f, Range= %f",fSigma,fRange));
AliDebug(1,"++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ \n");
Int_t ntrk=event->GetNumberOfTracks();
AliESDtrack **tracks=new AliESDtrack*[ntrk];
Int_t i;
for (i=0; i<ntrk; i++) {
AliESDtrack *t=event->GetTrack(i);
tracks[i]=t;
}
for (i=0; i<ntrk; i++) {
AliESDtrack *t=tracks[i];
if ((t->GetStatus()&AliESDtrack::kTOFout)==0) continue;
if ((t->GetStatus()&AliESDtrack::kTIME)==0) continue;
Double_t tof=t->GetTOFsignal()-timeZero;
Double_t time[10]; t->GetIntegratedTimes(time);
Double_t p[10];
Double_t mom=t->GetP();
Bool_t mismatch=kTRUE, heavy=kTRUE;
for (Int_t j=0; j<AliPID::kSPECIES; j++) {
Double_t mass=AliPID::ParticleMass(j);
Double_t dpp=0.01; //mean relative pt resolution;
if (mom>0.5) dpp=0.01*mom;
Double_t sigma=dpp*time[j]/(1.+ mom*mom/(mass*mass));
sigma=TMath::Sqrt(sigma*sigma + fSigma*fSigma);
if (TMath::Abs(tof-time[j]) > fRange*sigma) {
p[j]=TMath::Exp(-0.5*fRange*fRange)/sigma;
} else
p[j]=TMath::Exp(-0.5*(tof-time[j])*(tof-time[j])/(sigma*sigma))/sigma;
// Check the mismatching
Double_t pm=GetMismatchProbability(mom,mass);
if (p[j]>pm) mismatch=kFALSE;
// Check for particles heavier than (AliPID::kSPECIES - 1)
if (tof < (time[j] + fRange*sigma)) heavy=kFALSE;
}
if (mismatch)
for (Int_t j=0; j<AliPID::kSPECIES; j++) p[j]=1/AliPID::kSPECIES;
t->SetTOFpid(p);
if (heavy) t->ResetStatus(AliESDtrack::kTOFpid);
}
delete[] tracks;
return 0;
}
//_________________________________________________________________________
Int_t AliTOFpidESD::MakePID(AliESDEvent *event)
{
//
// This function calculates the "detector response" PID probabilities
// Just for a bare hint...
Int_t ntrk=event->GetNumberOfTracks();
AliESDtrack **tracks=new AliESDtrack*[ntrk];
Int_t i;
for (i=0; i<ntrk; i++) {
AliESDtrack *t=event->GetTrack(i);
tracks[i]=t;
}
for (i=0; i<ntrk; i++) {
AliESDtrack *t=tracks[i];
if ((t->GetStatus()&AliESDtrack::kTOFout)==0) continue;
if ((t->GetStatus()&AliESDtrack::kTIME)==0) continue;
Double_t tof=t->GetTOFsignal();
Double_t time[10]; t->GetIntegratedTimes(time);
Double_t p[10];
Double_t mom=t->GetP();
Bool_t mismatch=kTRUE, heavy=kTRUE;
for (Int_t j=0; j<AliPID::kSPECIES; j++) {
Double_t mass=AliPID::ParticleMass(j);
Double_t dpp=0.01; //mean relative pt resolution;
if (mom>0.5) dpp=0.01*mom;
Double_t sigma=dpp*time[j]/(1.+ mom*mom/(mass*mass));
sigma=TMath::Sqrt(sigma*sigma + fSigma*fSigma);
if (TMath::Abs(tof-time[j]) > fRange*sigma) {
p[j]=TMath::Exp(-0.5*fRange*fRange)/sigma;
} else
p[j]=TMath::Exp(-0.5*(tof-time[j])*(tof-time[j])/(sigma*sigma))/sigma;
// Check the mismatching
Double_t pm=GetMismatchProbability(mom,mass);
if (p[j]>pm) mismatch=kFALSE;
// Check for particles heavier than (AliPID::kSPECIES - 1)
if (tof < (time[j] + fRange*sigma)) heavy=kFALSE;
}
if (mismatch)
for (Int_t j=0; j<AliPID::kSPECIES; j++) p[j]=1/AliPID::kSPECIES;
t->SetTOFpid(p);
if (heavy) t->ResetStatus(AliESDtrack::kTOFpid);
}
delete[] tracks;
return 0;
}
<commit_msg>Coding convention: RN17 rule violation -> suppression<commit_after>/**************************************************************************
* Copyright(c) 1998-1999, ALICE Experiment at CERN, All rights reserved. *
* *
* Author: The ALICE Off-line Project. *
* Contributors are mentioned in the code where appropriate. *
* *
* Permission to use, copy, modify and distribute this software and its *
* documentation strictly for non-commercial purposes is hereby granted *
* without fee, provided that the above copyright notice appears in all *
* copies and that both the copyright notice and this permission notice *
* appear in the supporting documentation. The authors make no claims *
* about the suitability of this software for any purpose. It is *
* provided "as is" without express or implied warranty. *
**************************************************************************/
//-----------------------------------------------------------------//
// //
// Implementation of the TOF PID class //
// Origin: Iouri Belikov, CERN, Jouri.Belikov@cern.ch //
// //
//-----------------------------------------------------------------//
#include "TMath.h"
#include "AliLog.h"
#include "AliESDtrack.h"
#include "AliESDEvent.h"
#include "AliTOFpidESD.h"
ClassImp(AliTOFpidESD)
//_________________________________________________________________________
AliTOFpidESD::AliTOFpidESD():
fSigma(0),
fRange(0),
fPmax(0) // zero at 0.5 GeV/c for pp
{
}
//_________________________________________________________________________
AliTOFpidESD::AliTOFpidESD(Double_t *param):
fSigma(param[0]),
fRange(param[1]),
fPmax(0) // zero at 0.5 GeV/c for pp
{
//
// The main constructor
//
//
//fPmax=TMath::Exp(-0.5*3*3)/fSigma; // ~3 sigma at 0.5 GeV/c for PbPb
}
Double_t
AliTOFpidESD::GetMismatchProbability(Double_t p, Double_t mass) const {
//
// Returns the probability of mismatching
// assuming 1/(p*beta)^2 scaling
//
const Double_t km=0.5; // "reference" momentum (GeV/c)
Double_t ref2=km*km*km*km/(km*km + mass*mass);// "reference" (p*beta)^2
Double_t p2beta2=p*p*p*p/(p*p + mass*mass);
return fPmax*ref2/p2beta2;
}
//_________________________________________________________________________
Int_t AliTOFpidESD::MakePID(AliESDEvent *event, Double_t timeZero)
{
//
// This function calculates the "detector response" PID probabilities
// Just for a bare hint...
AliDebug(1,Form("TOF PID Parameters: Sigma (ps)= %f, Range= %f",fSigma,fRange));
AliDebug(1,"++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ \n");
Int_t ntrk=event->GetNumberOfTracks();
AliESDtrack **tracks=new AliESDtrack*[ntrk];
Int_t i;
for (i=0; i<ntrk; i++) {
AliESDtrack *t=event->GetTrack(i);
tracks[i]=t;
}
for (i=0; i<ntrk; i++) {
AliESDtrack *t=tracks[i];
if ((t->GetStatus()&AliESDtrack::kTOFout)==0) continue;
if ((t->GetStatus()&AliESDtrack::kTIME)==0) continue;
Double_t tof=t->GetTOFsignal()-timeZero;
Double_t time[10]; t->GetIntegratedTimes(time);
Double_t p[10];
Double_t mom=t->GetP();
Bool_t mismatch=kTRUE, heavy=kTRUE;
for (Int_t j=0; j<AliPID::kSPECIES; j++) {
Double_t mass=AliPID::ParticleMass(j);
Double_t dpp=0.01; //mean relative pt resolution;
if (mom>0.5) dpp=0.01*mom;
Double_t sigma=dpp*time[j]/(1.+ mom*mom/(mass*mass));
sigma=TMath::Sqrt(sigma*sigma + fSigma*fSigma);
if (TMath::Abs(tof-time[j]) > fRange*sigma) {
p[j]=TMath::Exp(-0.5*fRange*fRange)/sigma;
} else
p[j]=TMath::Exp(-0.5*(tof-time[j])*(tof-time[j])/(sigma*sigma))/sigma;
// Check the mismatching
Double_t pm=GetMismatchProbability(mom,mass);
if (p[j]>pm) mismatch=kFALSE;
// Check for particles heavier than (AliPID::kSPECIES - 1)
if (tof < (time[j] + fRange*sigma)) heavy=kFALSE;
}
if (mismatch)
for (Int_t j=0; j<AliPID::kSPECIES; j++) p[j]=1/AliPID::kSPECIES;
t->SetTOFpid(p);
if (heavy) t->ResetStatus(AliESDtrack::kTOFpid);
}
delete[] tracks;
return 0;
}
//_________________________________________________________________________
Int_t AliTOFpidESD::MakePID(AliESDEvent *event)
{
//
// This function calculates the "detector response" PID probabilities
// Just for a bare hint...
Int_t ntrk=event->GetNumberOfTracks();
AliESDtrack **tracks=new AliESDtrack*[ntrk];
Int_t i;
for (i=0; i<ntrk; i++) {
AliESDtrack *t=event->GetTrack(i);
tracks[i]=t;
}
for (i=0; i<ntrk; i++) {
AliESDtrack *t=tracks[i];
if ((t->GetStatus()&AliESDtrack::kTOFout)==0) continue;
if ((t->GetStatus()&AliESDtrack::kTIME)==0) continue;
Double_t tof=t->GetTOFsignal();
Double_t time[10]; t->GetIntegratedTimes(time);
Double_t p[10];
Double_t mom=t->GetP();
Bool_t mismatch=kTRUE, heavy=kTRUE;
for (Int_t j=0; j<AliPID::kSPECIES; j++) {
Double_t mass=AliPID::ParticleMass(j);
Double_t dpp=0.01; //mean relative pt resolution;
if (mom>0.5) dpp=0.01*mom;
Double_t sigma=dpp*time[j]/(1.+ mom*mom/(mass*mass));
sigma=TMath::Sqrt(sigma*sigma + fSigma*fSigma);
if (TMath::Abs(tof-time[j]) > fRange*sigma) {
p[j]=TMath::Exp(-0.5*fRange*fRange)/sigma;
} else
p[j]=TMath::Exp(-0.5*(tof-time[j])*(tof-time[j])/(sigma*sigma))/sigma;
// Check the mismatching
Double_t pm=GetMismatchProbability(mom,mass);
if (p[j]>pm) mismatch=kFALSE;
// Check for particles heavier than (AliPID::kSPECIES - 1)
if (tof < (time[j] + fRange*sigma)) heavy=kFALSE;
}
if (mismatch)
for (Int_t j=0; j<AliPID::kSPECIES; j++) p[j]=1/AliPID::kSPECIES;
t->SetTOFpid(p);
if (heavy) t->ResetStatus(AliESDtrack::kTOFpid);
}
delete[] tracks;
return 0;
}
<|endoftext|> |
<commit_before>/*
This file is part of cpp-ethereum.
cpp-ethereum is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
cpp-ethereum is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with cpp-ethereum. If not, see <http://www.gnu.org/licenses/>.
*/
/** @file net.cpp
* @author Alex Leverington <nessence@gmail.com>
* @date 2014
*/
#include <boost/test/unit_test.hpp>
#include <libdevcore/Worker.h>
#include <libdevcrypto/Common.h>
#include <libp2p/UDP.h>
#include <libp2p/NodeTable.h>
using namespace std;
using namespace dev;
using namespace dev::p2p;
namespace ba = boost::asio;
namespace bi = ba::ip;
BOOST_AUTO_TEST_SUITE(p2p)
/**
* Only used for testing. Not useful beyond tests.
*/
class TestHost: public Worker
{
public:
TestHost(): Worker("test",0), m_io() {};
virtual ~TestHost() { m_io.stop(); stopWorking(); }
void start() { startWorking(); }
void doWork() { m_io.run(); }
protected:
ba::io_service m_io;
};
struct TestNodeTable: public NodeTable
{
/// Constructor
using NodeTable::NodeTable;
void setup(std::vector<std::pair<KeyPair,unsigned>> const& _testNodes)
{
/// Phase 1 test: populate with pings
/// Phase 2 test: pre-populate *expected* ping-responses, send pings
bi::address ourIp = bi::address::from_string("127.0.0.1");
uint16_t ourPort = 30300;
bi::udp::endpoint ourEndpoint(ourIp, ourPort);
for (auto& n: _testNodes)
ping(bi::udp::endpoint(ourIp, n.second));
// wait 1ms between each send
// send PingNode for each s_bootstrapNodes
// wait until nodecount is s_testNodes.count()
}
void reset()
{
Guard l(x_state);
for (auto& n: m_state) n.nodes.clear();
}
};
/**
* Only used for testing. Not useful beyond tests.
*/
struct TestNodeTableHost: public TestHost
{
TestNodeTableHost(): m_alias(KeyPair::create()), nodeTable(new TestNodeTable(m_io, m_alias)) {};
void generateTestNodes(int _count = 10)
{
asserts(_count < 1000);
static uint16_t s_basePort = 30500;
m_testNodes.clear();
for (auto i = 0; i < _count; i++)
{
KeyPair k = KeyPair::create();
m_testNodes.push_back(make_pair(k,s_basePort+i));
testNodes.push_back(make_shared<TestNodeTable>(m_io,k,s_basePort+i));
}
}
std::vector<std::pair<KeyPair,unsigned>> m_testNodes; // keypair and port
void setup()
{
generateTestNodes();
nodeTable->setup(m_testNodes);
}
KeyPair m_alias;
shared_ptr<TestNodeTable> nodeTable;
std::vector<shared_ptr<TestNodeTable>> testNodes;
};
class TestUDPSocket: UDPSocketEvents, public TestHost
{
public:
TestUDPSocket(): m_socket(new UDPSocket<TestUDPSocket, 1024>(m_io, *this, 30300)) {}
void onDisconnected(UDPSocketFace*) {};
void onReceived(UDPSocketFace*, bi::udp::endpoint const&, bytesConstRef _packet) { if (_packet.toString() == "AAAA") success = true; }
shared_ptr<UDPSocket<TestUDPSocket, 1024>> m_socket;
bool success = false;
};
BOOST_AUTO_TEST_CASE(kademlia)
{
TestNodeTableHost node;
node.start();
node.nodeTable->join(); // ideally, joining with empty node table logs warning we can check for
node.setup();
sleep(1);
}
BOOST_AUTO_TEST_CASE(test_txrx_one)
{
UDPDatagram d(bi::udp::endpoint(boost::asio::ip::address::from_string("127.0.0.1"), 30300), bytes({65,65,65,65}));
TestUDPSocket a; a.m_socket->connect(); a.start();
a.m_socket->send(d);
sleep(1);
BOOST_REQUIRE_EQUAL(true, a.success);
}
BOOST_AUTO_TEST_SUITE_END()
<commit_msg>basic implementation of packets<commit_after>/*
This file is part of cpp-ethereum.
cpp-ethereum is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
cpp-ethereum is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with cpp-ethereum. If not, see <http://www.gnu.org/licenses/>.
*/
/** @file net.cpp
* @author Alex Leverington <nessence@gmail.com>
* @date 2014
*/
#include <boost/test/unit_test.hpp>
#include <libdevcore/Worker.h>
#include <libdevcrypto/Common.h>
#include <libp2p/UDP.h>
#include <libp2p/NodeTable.h>
using namespace std;
using namespace dev;
using namespace dev::p2p;
namespace ba = boost::asio;
namespace bi = ba::ip;
BOOST_AUTO_TEST_SUITE(p2p)
/**
* Only used for testing. Not useful beyond tests.
*/
class TestHost: public Worker
{
public:
TestHost(): Worker("test",0), m_io() {};
virtual ~TestHost() { m_io.stop(); stopWorking(); }
void start() { startWorking(); }
void doWork() { m_io.run(); }
protected:
ba::io_service m_io;
};
struct TestNodeTable: public NodeTable
{
/// Constructor
using NodeTable::NodeTable;
void setup(std::vector<std::pair<KeyPair,unsigned>> const& _testNodes)
{
/// Phase 2 test: pre-populate *expected* ping-responses, send pings
bi::address ourIp = bi::address::from_string("127.0.0.1");
uint16_t ourPort = 30300;
bi::udp::endpoint ourEndpoint(ourIp, ourPort);
for (auto& n: _testNodes)
ping(bi::udp::endpoint(ourIp, n.second));
}
void reset()
{
Guard l(x_state);
for (auto& n: m_state) n.nodes.clear();
}
};
/**
* Only used for testing. Not useful beyond tests.
*/
struct TestNodeTableHost: public TestHost
{
TestNodeTableHost(): m_alias(KeyPair::create()), nodeTable(new TestNodeTable(m_io, m_alias)) {};
void generateTestNodes(int _count = 10)
{
asserts(_count < 1000);
static uint16_t s_basePort = 30500;
m_testNodes.clear();
for (auto i = 0; i < _count; i++)
{
KeyPair k = KeyPair::create();
m_testNodes.push_back(make_pair(k,s_basePort+i));
testNodes.push_back(make_shared<TestNodeTable>(m_io,k,s_basePort+i));
}
}
std::vector<std::pair<KeyPair,unsigned>> m_testNodes; // keypair and port
void setup()
{
generateTestNodes();
nodeTable->setup(m_testNodes);
}
KeyPair m_alias;
shared_ptr<TestNodeTable> nodeTable;
std::vector<shared_ptr<TestNodeTable>> testNodes;
};
class TestUDPSocket: UDPSocketEvents, public TestHost
{
public:
TestUDPSocket(): m_socket(new UDPSocket<TestUDPSocket, 1024>(m_io, *this, 30300)) {}
void onDisconnected(UDPSocketFace*) {};
void onReceived(UDPSocketFace*, bi::udp::endpoint const&, bytesConstRef _packet) { if (_packet.toString() == "AAAA") success = true; }
shared_ptr<UDPSocket<TestUDPSocket, 1024>> m_socket;
bool success = false;
};
BOOST_AUTO_TEST_CASE(kademlia)
{
TestNodeTableHost node;
node.start();
node.nodeTable->join(); // ideally, joining with empty node table logs warning we can check for
node.setup();
sleep(1);
}
BOOST_AUTO_TEST_CASE(test_txrx_one)
{
UDPDatagram d(bi::udp::endpoint(boost::asio::ip::address::from_string("127.0.0.1"), 30300), bytes({65,65,65,65}));
TestUDPSocket a; a.m_socket->connect(); a.start();
a.m_socket->send(d);
sleep(1);
BOOST_REQUIRE_EQUAL(true, a.success);
}
BOOST_AUTO_TEST_SUITE_END()
<|endoftext|> |
<commit_before>/* Copyright 2012-present Facebook, Inc.
* Licensed under the Apache License, Version 2.0 */
#include "watchman.h"
#include <getopt.h>
using namespace watchman;
#define IS_REQUIRED(x) (x) == REQ_STRING
/* One does not simply use getopt_long() */
void usage(struct watchman_getopt* opts, FILE* where) {
int i;
size_t len;
size_t longest = 0;
const char* label;
fprintf(where, "Usage: watchman [opts] command\n");
/* measure up option names so we can format nicely */
for (i = 0; opts[i].optname; i++) {
label = opts[i].arglabel ? opts[i].arglabel : "ARG";
len = strlen(opts[i].optname);
switch (opts[i].argtype) {
case REQ_STRING:
len += strlen(label) + strlen("=");
break;
default:;
}
if (opts[i].shortopt) {
len += strlen("-X, ");
}
if (len > longest) {
longest = len;
}
}
/* space between option definition and help text */
longest += 3;
for (i = 0; opts[i].optname; i++) {
char buf[80];
if (!opts[i].helptext) {
// This is a signal that this option shouldn't be printed out.
continue;
}
label = opts[i].arglabel ? opts[i].arglabel : "ARG";
fprintf(where, "\n ");
if (opts[i].shortopt) {
fprintf(where, "-%c, ", opts[i].shortopt);
} else {
fprintf(where, " ");
}
switch (opts[i].argtype) {
case REQ_STRING:
snprintf(buf, sizeof(buf), "--%s=%s", opts[i].optname, label);
break;
default:
snprintf(buf, sizeof(buf), "--%s", opts[i].optname);
break;
}
fprintf(where, "%-*s ", (unsigned int)longest, buf);
fprintf(where, "%s", opts[i].helptext);
fprintf(where, "\n");
}
print_command_list_for_help(where);
fprintf(
where,
"\n"
"See https://github.com/facebook/watchman#watchman for more help\n"
"\n"
"Watchman, by Wez Furlong.\n"
"Copyright 2012-2017 Facebook, Inc.\n");
exit(1);
}
bool w_getopt(
struct watchman_getopt* opts,
int* argcp,
char*** argvp,
char*** daemon_argvp) {
int num_opts, i;
char* nextshort;
int argc = *argcp;
char** argv = *argvp;
int long_pos = -1;
int res;
int num_daemon = 0;
/* first build up the getopt_long bits that we need */
for (num_opts = 0; opts[num_opts].optname; num_opts++) {
;
}
/* to hold the args we pass to the daemon */
auto daemon_argv = (char**)calloc(num_opts + 1, sizeof(char*));
if (!daemon_argv) {
log(FATAL, "calloc daemon opts\n");
}
*daemon_argvp = daemon_argv;
/* something to hold the long options */
auto long_opts = (option*)calloc(num_opts + 1, sizeof(struct option));
if (!long_opts) {
log(FATAL, "calloc struct option\n");
}
/* and the short options */
auto shortopts = (char*)malloc((1 + num_opts) * 2);
if (!shortopts) {
log(FATAL, "malloc shortopts\n");
}
nextshort = shortopts;
nextshort[0] = ':';
nextshort++;
/* now transfer information into the space we made */
for (i = 0; i < num_opts; i++) {
long_opts[i].name = (char*)opts[i].optname;
long_opts[i].val = opts[i].shortopt;
switch (opts[i].argtype) {
case OPT_NONE:
long_opts[i].has_arg = no_argument;
break;
case REQ_STRING:
case REQ_INT:
long_opts[i].has_arg = required_argument;
break;
}
if (opts[i].shortopt) {
nextshort[0] = (char)opts[i].shortopt;
nextshort++;
if (long_opts[i].has_arg != no_argument) {
nextshort[0] = ':';
nextshort++;
}
}
}
nextshort[0] = 0;
while ((res = getopt_long(argc, argv, shortopts, long_opts, &long_pos)) !=
-1) {
struct watchman_getopt* o;
switch (res) {
case ':':
/* missing option argument.
* Check to see if it was actually optional */
for (long_pos = 0; long_pos < num_opts; long_pos++) {
if (opts[long_pos].shortopt == optopt) {
if (IS_REQUIRED(opts[long_pos].argtype)) {
fprintf(
stderr,
"--%s (-%c) requires an argument",
opts[long_pos].optname,
opts[long_pos].shortopt);
return false;
}
}
}
break;
case '?':
/* unknown option */
fprintf(stderr, "Unknown or invalid option! %s\n", argv[optind - 1]);
usage(opts, stderr);
return false;
default:
if (res == 0) {
/* we got a long option */
o = &opts[long_pos];
} else {
/* map short option to the real thing */
o = NULL;
for (long_pos = 0; long_pos < num_opts; long_pos++) {
if (opts[long_pos].shortopt == res) {
o = &opts[long_pos];
break;
}
}
}
if (o->is_daemon) {
auto value = folly::to<std::string>(
"--", o->optname, "=", optarg ? optarg : "");
// we deliberately leak this value to the caller
daemon_argv[num_daemon++] = strdup(value.c_str());
}
/* store the argument if we found one */
if (o->argtype != OPT_NONE && o->val && optarg) {
switch (o->argtype) {
case REQ_INT: {
auto ival = atoi(optarg);
*(int*)o->val = ival;
cfg_set_arg(o->optname, json_integer(ival));
break;
}
case REQ_STRING: {
auto sval = typed_string_to_json(optarg, W_STRING_UNICODE);
*(std::string*)o->val = optarg;
cfg_set_arg(o->optname, sval);
break;
}
case OPT_NONE:;
}
}
if (o->argtype == OPT_NONE && o->val) {
auto bval = json_true();
*(int*)o->val = 1;
cfg_set_arg(o->optname, bval);
}
}
long_pos = -1;
}
free(long_opts);
free(shortopts);
*argcp = argc - optind;
*argvp = argv + optind;
return true;
}
/* vim:ts=2:sw=2:et:
*/
<commit_msg>update copyright year to 2020 in CLI usage output<commit_after>/* Copyright 2012-present Facebook, Inc.
* Licensed under the Apache License, Version 2.0 */
#include "watchman.h"
#include <getopt.h>
using namespace watchman;
#define IS_REQUIRED(x) (x) == REQ_STRING
/* One does not simply use getopt_long() */
void usage(struct watchman_getopt* opts, FILE* where) {
int i;
size_t len;
size_t longest = 0;
const char* label;
fprintf(where, "Usage: watchman [opts] command\n");
/* measure up option names so we can format nicely */
for (i = 0; opts[i].optname; i++) {
label = opts[i].arglabel ? opts[i].arglabel : "ARG";
len = strlen(opts[i].optname);
switch (opts[i].argtype) {
case REQ_STRING:
len += strlen(label) + strlen("=");
break;
default:;
}
if (opts[i].shortopt) {
len += strlen("-X, ");
}
if (len > longest) {
longest = len;
}
}
/* space between option definition and help text */
longest += 3;
for (i = 0; opts[i].optname; i++) {
char buf[80];
if (!opts[i].helptext) {
// This is a signal that this option shouldn't be printed out.
continue;
}
label = opts[i].arglabel ? opts[i].arglabel : "ARG";
fprintf(where, "\n ");
if (opts[i].shortopt) {
fprintf(where, "-%c, ", opts[i].shortopt);
} else {
fprintf(where, " ");
}
switch (opts[i].argtype) {
case REQ_STRING:
snprintf(buf, sizeof(buf), "--%s=%s", opts[i].optname, label);
break;
default:
snprintf(buf, sizeof(buf), "--%s", opts[i].optname);
break;
}
fprintf(where, "%-*s ", (unsigned int)longest, buf);
fprintf(where, "%s", opts[i].helptext);
fprintf(where, "\n");
}
print_command_list_for_help(where);
fprintf(
where,
"\n"
"See https://github.com/facebook/watchman#watchman for more help\n"
"\n"
"Watchman, by Wez Furlong.\n"
"Copyright 2012-2020 Facebook, Inc.\n");
exit(1);
}
bool w_getopt(
struct watchman_getopt* opts,
int* argcp,
char*** argvp,
char*** daemon_argvp) {
int num_opts, i;
char* nextshort;
int argc = *argcp;
char** argv = *argvp;
int long_pos = -1;
int res;
int num_daemon = 0;
/* first build up the getopt_long bits that we need */
for (num_opts = 0; opts[num_opts].optname; num_opts++) {
;
}
/* to hold the args we pass to the daemon */
auto daemon_argv = (char**)calloc(num_opts + 1, sizeof(char*));
if (!daemon_argv) {
log(FATAL, "calloc daemon opts\n");
}
*daemon_argvp = daemon_argv;
/* something to hold the long options */
auto long_opts = (option*)calloc(num_opts + 1, sizeof(struct option));
if (!long_opts) {
log(FATAL, "calloc struct option\n");
}
/* and the short options */
auto shortopts = (char*)malloc((1 + num_opts) * 2);
if (!shortopts) {
log(FATAL, "malloc shortopts\n");
}
nextshort = shortopts;
nextshort[0] = ':';
nextshort++;
/* now transfer information into the space we made */
for (i = 0; i < num_opts; i++) {
long_opts[i].name = (char*)opts[i].optname;
long_opts[i].val = opts[i].shortopt;
switch (opts[i].argtype) {
case OPT_NONE:
long_opts[i].has_arg = no_argument;
break;
case REQ_STRING:
case REQ_INT:
long_opts[i].has_arg = required_argument;
break;
}
if (opts[i].shortopt) {
nextshort[0] = (char)opts[i].shortopt;
nextshort++;
if (long_opts[i].has_arg != no_argument) {
nextshort[0] = ':';
nextshort++;
}
}
}
nextshort[0] = 0;
while ((res = getopt_long(argc, argv, shortopts, long_opts, &long_pos)) !=
-1) {
struct watchman_getopt* o;
switch (res) {
case ':':
/* missing option argument.
* Check to see if it was actually optional */
for (long_pos = 0; long_pos < num_opts; long_pos++) {
if (opts[long_pos].shortopt == optopt) {
if (IS_REQUIRED(opts[long_pos].argtype)) {
fprintf(
stderr,
"--%s (-%c) requires an argument",
opts[long_pos].optname,
opts[long_pos].shortopt);
return false;
}
}
}
break;
case '?':
/* unknown option */
fprintf(stderr, "Unknown or invalid option! %s\n", argv[optind - 1]);
usage(opts, stderr);
return false;
default:
if (res == 0) {
/* we got a long option */
o = &opts[long_pos];
} else {
/* map short option to the real thing */
o = NULL;
for (long_pos = 0; long_pos < num_opts; long_pos++) {
if (opts[long_pos].shortopt == res) {
o = &opts[long_pos];
break;
}
}
}
if (o->is_daemon) {
auto value = folly::to<std::string>(
"--", o->optname, "=", optarg ? optarg : "");
// we deliberately leak this value to the caller
daemon_argv[num_daemon++] = strdup(value.c_str());
}
/* store the argument if we found one */
if (o->argtype != OPT_NONE && o->val && optarg) {
switch (o->argtype) {
case REQ_INT: {
auto ival = atoi(optarg);
*(int*)o->val = ival;
cfg_set_arg(o->optname, json_integer(ival));
break;
}
case REQ_STRING: {
auto sval = typed_string_to_json(optarg, W_STRING_UNICODE);
*(std::string*)o->val = optarg;
cfg_set_arg(o->optname, sval);
break;
}
case OPT_NONE:;
}
}
if (o->argtype == OPT_NONE && o->val) {
auto bval = json_true();
*(int*)o->val = 1;
cfg_set_arg(o->optname, bval);
}
}
long_pos = -1;
}
free(long_opts);
free(shortopts);
*argcp = argc - optind;
*argvp = argv + optind;
return true;
}
/* vim:ts=2:sw=2:et:
*/
<|endoftext|> |
<commit_before>/*
Implements linear-time construction of (generalized) suffix tree
Sample input: "abcd$xyz#", where $ and # are delimeters
Delimeters determined by isDelim
Primary methods:
occurrences(pattern):
returns how many times pattern occurred across all input strings
longestRepeat(vector of strings, k)
Let Q = substrings that appear multiple times and in >k input strings
method fills vector with longest such Q
returns length of such strings
*/
#include <map>
#include <set>
#include <stack>
#include <string>
#include <limits>
#include <algorithm>
#include <iostream>
#include <sstream>
using namespace std;
//text has characters in range [LOWER,UPPER]
const char LOWER = 'a';
const char UPPER = 'z';
char ithDelim(int i){
char ans = 0;
if (i < LOWER-1) { ans = (char)(i+1); }
else { ans = (char) (UPPER+1 + (i+1 - LOWER)); }
//cerr << (int)ans << endl;
return ans;
}
struct SuffixTree {
//MUST DEFINE DELIMITERS OF GENERALIZED SUFFIX TREE
bool isDelim(char c){
return (c < LOWER) || (c > UPPER);
}
static const int INF = 1<<30;
int last;
string str;
struct Node;
struct Edge {
int a,b;
Node *begin,*end;
SuffixTree* tree;
Edge(int a, int b, Node *end, SuffixTree* tree)
: a(a), b(b), begin(NULL), end(end), tree(tree) {}
char getFirst() const { return tree->str[a]; }
int size() const { return min(tree->last,b)-a+1; }
friend ostream& operator<<(ostream& out, Edge& e);
};
struct Node {
Edge* inEdge;
map<char,Edge*> edges;
Node* suffix;
int a,b,leavesBelow,distinctDelims;
SuffixTree* tree;
Node(SuffixTree* tree)
: tree(tree), leavesBelow(0), distinctDelims(0), inEdge(NULL) {}
void add(Edge* e) { edges[e->getFirst()] = e; }
Edge* operator[](char c) { return edges[c]; }
int numChildren() { return edges.size(); }
friend ostream& operator<<(ostream& out, Node&);
};
Node *root, *sentinel;
Node* getRoot() { return root; }
const string& getStr() const { return str; }
void setPrefix(Node* n, Edge* e, int len) {
map<char,Edge*>::iterator it = n->edges.begin();
for (; it != n->edges.end(); ++it) {
Edge *edge = it->second;
setPrefix(edge->end,edge,len+min(edge->b,last)-edge->a+1);
}
if (e) {
n->b = min(e->b,last);
n->a = n->b - len + 1;
}
else {
n->a = 0;
n->b = -1;
}
}
Node* testAndSplit(Node* s, int k, int p, char c) {
if (k > p) {
return s == sentinel ? NULL : (*s)[c] == NULL ? s : NULL;
}
Edge* e = (*s)[str[k]];
if (c == str[e->a+p-k+1]) return NULL;
Node* r = new Node(this);
Edge* re = new Edge(e->a+p-k+1,e->b,e->end,this);
r->add(re);
Edge* se = new Edge(e->a,e->a+p-k,r,this);
s->add(se);
return r;
}
Node* canonize(Node* s, int& k, int p) {
if (p < k) { return s; }
if (s == sentinel) {
s = root;
++k;
if (p < k) { return s; }
}
Edge* e = (*s)[str[k]];
while (e->b - e->a <= p - k) {
k = k + e->b - e->a + 1;
s = e->end;
if (k <= p) e = (*s)[str[k]];
}
return s;
}
Node* update(Node* s, int& k, int i) {
Node *oldr = root, *r = testAndSplit(s,k,i-1,str[i]);
while (r) {
Node* rp = new Node(this);
Edge* e = new Edge(i,INF,rp,this);
r->add(e);
if (oldr != root) { oldr->suffix = r; }
oldr = r;
s = canonize(s->suffix,k,i-1);
r = testAndSplit(s,k,i-1,str[i]);
}
if (oldr != root) { oldr->suffix = s; }
return s;
}
void buildTree() {
root = new Node(this);
sentinel = new Node(this);
root->suffix = sentinel;
Node* s = root;
int k = 0;
last = -1;
for (int i = 0; i < (int)str.size(); ++i) {
++last;
s = update(s,k,i);
s = canonize(s,k,i);
}
}
int fix(int x) const { return x == INF ? last : x; }
friend ostream& operator<<(ostream& out, SuffixTree& t);
ostream& prettyFormat(ostream& out, Node* n, int tab) const {
out << string(tab,' ') << "\"" << *n << "\"" << n->distinctDelims << endl;
map<char,Edge*>::iterator it = n->edges.begin();
for (; it != n->edges.end(); ++it) {
Edge* e = it->second;
out << string(tab,' ') << it->first << " : "
<< *e << " = " << e->a << ',' << fix(e->b) << ',' << e->size() << endl;
prettyFormat(out,e->end,tab+2);
}
return out;
}
//number of leaves in subtree
//number of distinct delimiters
int postprocess(Node* n, set<char>& delims) {
for(auto p: n->edges){
//assign parent pointers
Edge* e = p.second;
Node* child = e->end;
child->inEdge = e;
e->begin = n;
//count number of leaves in subtree
set<char> childDelims;
n->leavesBelow += postprocess(child, childDelims);
for(auto c: childDelims) { delims.insert(c); }
}
//leaf
if (n->numChildren() == 0) {
n->leavesBelow = 1;
Edge* inEdge = n->inEdge;
for(int i = 0; i < inEdge->size(); i++){
if (isDelim(str[inEdge->a + i])) {
inEdge->b = inEdge->a + i;
n->b = inEdge->b;
break;
}
}
int index = inEdge->a + inEdge->size() - 1;
delims.insert(str[index]);
}
n->distinctDelims = delims.size();
return n->leavesBelow;
}
SuffixTree(const string& str) : str(str) {
buildTree();
setPrefix(root,NULL,0);
set<char> delims;
postprocess(root,delims);
}
void destroyNode(Node* n){
for(auto p: n->edges){
Edge* e = p.second;
destroyNode(e->end);
delete e;
}
delete n;
}
~SuffixTree(){
destroyNode(root);
delete sentinel;
}
int occurrences(const string& s, int index, Node* n){
//cerr << "Called occurrences()" << endl;
if (n->numChildren() == 0) {
//cerr << "No children" << endl;
return 0;
}
if (n->edges.find(s[index]) == n->edges.end()) {
//cerr << "Cannot find " << s[index] << endl;
return 0;
}
Edge* e = n->edges[s[index]];
for(int i = e->a; i < e->a+e->size(); i++){
if (str[i] == s[index]) {
index++;
if (index == s.size()) { break; }
}
else { return 0; }
}
if (index == s.size()) { return max(1,e->end->leavesBelow); }
return occurrences(s,index,e->end);
}
int occurrences(const string& s){
return occurrences(s,0,root);
}
void longestRepeat(Node* n, int size, int& length,
vector<Node*>& ptrs, int threshold){
if (n != root
//repeats iff there are multiple leaves in the subtree
&& n->leavesBelow > 1
//longest
&& size >= length
//check if the number of input strings is above the specified threshold
&& n->distinctDelims > threshold
) {
if (size > length) {
length = size;
ptrs.clear();
}
ptrs.push_back(n);
}
for(auto p: n->edges){
Edge* e = p.second;
longestRepeat(e->end, size+e->size(), length, ptrs, threshold);
}
}
int longestRepeat(vector<string>& longest, int threshold=0){
int length = 0;
vector<Node*> ptrs;
longestRepeat(root, 0, length, ptrs, threshold);
//reconstruct by walking up to root
for (auto p: ptrs) {
Node* ptr = p;
string cur = "";
stack<pair<int,int> > order;
while(ptr != root) {
order.push({ptr->inEdge->a, ptr->inEdge->b});
ptr = ptr->inEdge->begin;
}
while(!order.empty()){
pair<int,int> p = order.top();
order.pop();
for(int i = p.first; i <= p.second; i++){
cur += str[i];
}
}
longest.push_back(cur);
}
return length;
}
};
ostream& operator<<(ostream& out, SuffixTree::Edge& e)
{ return out << e.tree->str.substr(e.a,e.size()); }
ostream& operator<<(ostream& out, SuffixTree::Node& n)
{ return out << n.tree->str.substr(n.a,min(n.b,n.tree->last)-n.a+1); }
ostream& operator<<(ostream& out, SuffixTree& t)
{ return t.prettyFormat(out, t.root, 0); }
int main(int argc, char** argv) {
SuffixTree t(argv[1]);
cout << t << endl;
/*
for(int i = 2; i < argc; i++){
printf("%s occurs %d times\n", argv[i], t.occurrences((string)argv[i]));
}
*/
vector<string> longest;
int x = t.longestRepeat(longest,1);
cout << "The longest common substrings:" << endl;
for(auto s: longest) {
cout << '\t' << s << endl;
}
return 0;
}
<commit_msg>More comments<commit_after>/*
Implements linear-time construction of (generalized) suffix tree
Sample input: "abcd$xyz#", where $ and # are delimeters of separate strings
Delimeters determined by the constants LOWER & UPPER
Use ithDelim() function to terminate the ith input
Based upon code shared by John Zhang. Where he got it is anybody's guess.
Primary methods (written by me, not in the original code):
occurrences(pattern):
returns how many times pattern occurred across all input strings
longestRepeat(empty string vector, k)
Let Q = substrings that appear multiple times and in >k input strings
this method fills vector with longest such Q
returns length of such strings
*/
#include <map>
#include <set>
#include <stack>
#include <string>
#include <limits>
#include <algorithm>
#include <iostream>
#include <sstream>
using namespace std;
//text has characters in range [LOWER,UPPER]
const char LOWER = 'a';
const char UPPER = 'z';
char ithDelim(int i){
char ans = 0;
if (i < LOWER-1) { ans = (char)(i+1); }
else { ans = (char) (UPPER+1 + (i+1 - LOWER)); }
//cerr << (int)ans << endl;
return ans;
}
struct SuffixTree {
bool isDelim(char c){
return (c < LOWER) || (c > UPPER);
}
static const int INF = 1<<30;
int last;
string str;
struct Node;
struct Edge {
int a,b;
Node *begin,*end;
SuffixTree* tree;
Edge(int a, int b, Node *end, SuffixTree* tree)
: a(a), b(b), begin(NULL), end(end), tree(tree) {}
char getFirst() const { return tree->str[a]; }
int size() const { return min(tree->last,b)-a+1; }
friend ostream& operator<<(ostream& out, Edge& e);
};
struct Node {
Edge* inEdge;
map<char,Edge*> edges;
Node* suffix;
int a,b,leavesBelow,distinctDelims;
SuffixTree* tree;
Node(SuffixTree* tree)
: tree(tree), leavesBelow(0), distinctDelims(0), inEdge(NULL) {}
void add(Edge* e) { edges[e->getFirst()] = e; }
Edge* operator[](char c) { return edges[c]; }
int numChildren() { return edges.size(); }
friend ostream& operator<<(ostream& out, Node&);
};
Node *root, *sentinel;
Node* getRoot() { return root; }
const string& getStr() const { return str; }
void setPrefix(Node* n, Edge* e, int len) {
map<char,Edge*>::iterator it = n->edges.begin();
for (; it != n->edges.end(); ++it) {
Edge *edge = it->second;
setPrefix(edge->end,edge,len+min(edge->b,last)-edge->a+1);
}
if (e) {
n->b = min(e->b,last);
n->a = n->b - len + 1;
}
else {
n->a = 0;
n->b = -1;
}
}
Node* testAndSplit(Node* s, int k, int p, char c) {
if (k > p) {
return s == sentinel ? NULL : (*s)[c] == NULL ? s : NULL;
}
Edge* e = (*s)[str[k]];
if (c == str[e->a+p-k+1]) return NULL;
Node* r = new Node(this);
Edge* re = new Edge(e->a+p-k+1,e->b,e->end,this);
r->add(re);
Edge* se = new Edge(e->a,e->a+p-k,r,this);
s->add(se);
return r;
}
Node* canonize(Node* s, int& k, int p) {
if (p < k) { return s; }
if (s == sentinel) {
s = root;
++k;
if (p < k) { return s; }
}
Edge* e = (*s)[str[k]];
while (e->b - e->a <= p - k) {
k = k + e->b - e->a + 1;
s = e->end;
if (k <= p) e = (*s)[str[k]];
}
return s;
}
Node* update(Node* s, int& k, int i) {
Node *oldr = root, *r = testAndSplit(s,k,i-1,str[i]);
while (r) {
Node* rp = new Node(this);
Edge* e = new Edge(i,INF,rp,this);
r->add(e);
if (oldr != root) { oldr->suffix = r; }
oldr = r;
s = canonize(s->suffix,k,i-1);
r = testAndSplit(s,k,i-1,str[i]);
}
if (oldr != root) { oldr->suffix = s; }
return s;
}
void buildTree() {
root = new Node(this);
sentinel = new Node(this);
root->suffix = sentinel;
Node* s = root;
int k = 0;
last = -1;
for (int i = 0; i < (int)str.size(); ++i) {
++last;
s = update(s,k,i);
s = canonize(s,k,i);
}
}
int fix(int x) const { return x == INF ? last : x; }
friend ostream& operator<<(ostream& out, SuffixTree& t);
ostream& prettyFormat(ostream& out, Node* n, int tab) const {
out << string(tab,' ') << "\"" << *n << "\"" << n->distinctDelims << endl;
map<char,Edge*>::iterator it = n->edges.begin();
for (; it != n->edges.end(); ++it) {
Edge* e = it->second;
out << string(tab,' ') << it->first << " : "
<< *e << " = " << e->a << ',' << fix(e->b) << ',' << e->size() << endl;
prettyFormat(out,e->end,tab+2);
}
return out;
}
//number of leaves in subtree
//number of distinct delimiters
int postprocess(Node* n, set<char>& delims) {
for(auto p: n->edges){
//assign parent pointers
Edge* e = p.second;
Node* child = e->end;
child->inEdge = e;
e->begin = n;
//count number of leaves in subtree
set<char> childDelims;
n->leavesBelow += postprocess(child, childDelims);
for(auto c: childDelims) { delims.insert(c); }
}
//leaf
if (n->numChildren() == 0) {
n->leavesBelow = 1;
Edge* inEdge = n->inEdge;
for(int i = 0; i < inEdge->size(); i++){
if (isDelim(str[inEdge->a + i])) {
inEdge->b = inEdge->a + i;
n->b = inEdge->b;
break;
}
}
int index = inEdge->a + inEdge->size() - 1;
delims.insert(str[index]);
}
n->distinctDelims = delims.size();
return n->leavesBelow;
}
SuffixTree(const string& str) : str(str) {
buildTree();
setPrefix(root,NULL,0);
set<char> delims;
postprocess(root,delims);
}
void destroyNode(Node* n){
for(auto p: n->edges){
Edge* e = p.second;
destroyNode(e->end);
delete e;
}
delete n;
}
~SuffixTree(){
destroyNode(root);
delete sentinel;
}
int occurrences(const string& s, int index, Node* n){
//cerr << "Called occurrences()" << endl;
if (n->numChildren() == 0) {
//cerr << "No children" << endl;
return 0;
}
if (n->edges.find(s[index]) == n->edges.end()) {
//cerr << "Cannot find " << s[index] << endl;
return 0;
}
Edge* e = n->edges[s[index]];
for(int i = e->a; i < e->a+e->size(); i++){
if (str[i] == s[index]) {
index++;
if (index == s.size()) { break; }
}
else { return 0; }
}
if (index == s.size()) { return max(1,e->end->leavesBelow); }
return occurrences(s,index,e->end);
}
int occurrences(const string& s){
return occurrences(s,0,root);
}
void longestRepeat(Node* n, int size, int& length,
vector<Node*>& ptrs, int threshold){
if (n != root
//repeats iff there are multiple leaves in the subtree
&& n->leavesBelow > 1
//longest
&& size >= length
//check if the number of input strings is above the specified threshold
&& n->distinctDelims > threshold
) {
if (size > length) {
length = size;
ptrs.clear();
}
ptrs.push_back(n);
}
for(auto p: n->edges){
Edge* e = p.second;
longestRepeat(e->end, size+e->size(), length, ptrs, threshold);
}
}
int longestRepeat(vector<string>& longest, int threshold=0){
int length = 0;
vector<Node*> ptrs;
longestRepeat(root, 0, length, ptrs, threshold);
//reconstruct by walking up to root
for (auto p: ptrs) {
Node* ptr = p;
string cur = "";
stack<pair<int,int> > order;
while(ptr != root) {
order.push({ptr->inEdge->a, ptr->inEdge->b});
ptr = ptr->inEdge->begin;
}
while(!order.empty()){
pair<int,int> p = order.top();
order.pop();
for(int i = p.first; i <= p.second; i++){
cur += str[i];
}
}
longest.push_back(cur);
}
return length;
}
};
ostream& operator<<(ostream& out, SuffixTree::Edge& e)
{ return out << e.tree->str.substr(e.a,e.size()); }
ostream& operator<<(ostream& out, SuffixTree::Node& n)
{ return out << n.tree->str.substr(n.a,min(n.b,n.tree->last)-n.a+1); }
ostream& operator<<(ostream& out, SuffixTree& t)
{ return t.prettyFormat(out, t.root, 0); }
int main(int argc, char** argv) {
SuffixTree t(argv[1]);
cout << t << endl;
/*
for(int i = 2; i < argc; i++){
printf("%s occurs %d times\n", argv[i], t.occurrences((string)argv[i]));
}
*/
vector<string> longest;
int x = t.longestRepeat(longest,1);
cout << "The longest common substrings:" << endl;
for(auto s: longest) {
cout << '\t' << s << endl;
}
return 0;
}
<|endoftext|> |
<commit_before>/*
* Copyright 2016 Nu-book Inc.
* Copyright 2016 ZXing authors
* Copyright 2020 Axel Waggershauser
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "QRDetector.h"
#include "BitMatrix.h"
#include "BitMatrixCursor.h"
#include "ConcentricFinder.h"
#include "DetectorResult.h"
#include "GridSampler.h"
#include "LogMatrix.h"
#include "PerspectiveTransform.h"
#include "QRVersion.h"
#include "RegressionLine.h"
#include <algorithm>
#include <cmath>
#include <cstdlib>
#include <limits>
#include <map>
#include <utility>
namespace ZXing::QRCode {
static auto FindFinderPatterns(const BitMatrix& image, bool tryHarder)
{
constexpr int MIN_SKIP = 3; // 1 pixel/module times 3 modules/center
constexpr int MAX_MODULES = 20 * 4 + 17; // support up to version 20 for mobile clients
constexpr auto PATTERN = FixedPattern<5, 7>{1, 1, 3, 1, 1};
// Let's assume that the maximum version QR Code we support takes up 1/4 the height of the
// image, and then account for the center being 3 modules in size. This gives the smallest
// number of pixels the center could be, so skip this often. When trying harder, look for all
// QR versions regardless of how dense they are.
int height = image.height();
int skip = (3 * height) / (4 * MAX_MODULES);
if (skip < MIN_SKIP || tryHarder)
skip = MIN_SKIP;
std::vector<ConcentricPattern> res;
for (int y = skip - 1; y < height; y += skip) {
PatternRow row;
image.getPatternRow(y, row);
PatternView next = row;
while (next = FindLeftGuard(next, 0, PATTERN, 0.5), next.isValid()) {
PointF p(next.pixelsInFront() + next[0] + next[1] + next[2] / 2.0, y + 0.5);
// make sure p is not 'inside' an already found pattern area
if (FindIf(res, [p](const auto& old) { return distance(p, old) < old.size / 2; }) == res.end()) {
auto pattern = LocateConcentricPattern(image, PATTERN, p,
Reduce(next) * 3 / 2); // 1.5 for very skewed samples
if (pattern) {
log(*pattern, 3);
res.push_back(*pattern);
}
}
next.skipPair();
next.skipPair();
next.extend();
}
}
return res;
}
struct FinderPatternSet
{
ConcentricPattern bl, tl, tr;
};
using FinderPatternSets = std::vector<FinderPatternSet>;
/**
* @brief GenerateFinderPatternSets
* @param patterns list of ConcentricPattern objects, i.e. found finder pattern squares
* @return list of plausible finder pattern sets, sorted by decreasing plausibility
*/
static FinderPatternSets GenerateFinderPatternSets(std::vector<ConcentricPattern>&& patterns)
{
std::sort(patterns.begin(), patterns.end(), [](const auto& a, const auto& b) { return a.size < b.size; });
auto sets = std::multimap<double, FinderPatternSet>();
auto squaredDistance = [](PointF a, PointF b) { return dot((a - b), (a - b)); };
int nbPatterns = Size(patterns);
for (int i = 0; i < nbPatterns - 2; i++) {
for (int j = i + 1; j < nbPatterns - 1; j++) {
for (int k = j + 1; k < nbPatterns - 0; k++) {
const auto* a = &patterns[i];
const auto* b = &patterns[j];
const auto* c = &patterns[k];
// if the pattern sizes are too different to be part of the same symbol, skip this
// and the rest of the innermost loop (sorted list)
if (c->size > a->size * 2)
break;
// Orders the three points in an order [A,B,C] such that AB is less than AC
// and BC is less than AC, and the angle between BC and BA is less than 180 degrees.
auto distAB = squaredDistance(*a, *b);
auto distBC = squaredDistance(*b, *c);
auto distAC = squaredDistance(*a, *c);
if (distBC >= distAB && distBC >= distAC) {
std::swap(a, b);
std::swap(distBC, distAC);
} else if (distAB >= distAC && distAB >= distBC) {
std::swap(b, c);
std::swap(distAB, distAC);
}
// Estimate the module count and ignore this set if it can not result in a valid decoding
if (auto moduleCount =
(std::sqrt(distAB) + std::sqrt(distBC)) / (2 * (a->size + b->size + c->size) / (3 * 7.f)) + 7;
moduleCount < 21 * 0.9 || moduleCount > 177 * 1.05)
continue;
// a^2 + b^2 = c^2 (Pythagorean theorem), and a = b (isosceles triangle).
// Since any right triangle satisfies the formula c^2 - b^2 - a^2 = 0,
// we need to check both two equal sides separately.
// The value of |c^2 - 2 * b^2| + |c^2 - 2 * a^2| increases as dissimilarity
// from isosceles right triangle.
double d = std::abs(distAC - 2 * distAB) + std::abs(distAC - 2 * distBC);
// Use cross product to figure out whether A and C are correct or flipped.
// This asks whether BC x BA has a positive z component, which is the arrangement
// we want for A, B, C. If it's negative then swap A and C.
if (cross(*c - *b, *a - *b) < 0)
std::swap(a, c);
// arbitrarily limit the number of potential sets
if (sets.size() < 16 || sets.crbegin()->first > d) {
sets.emplace(d, FinderPatternSet{*a, *b, *c});
if (sets.size() > 16)
sets.erase(std::prev(sets.end()));
}
}
}
}
// convert from multimap to vector
FinderPatternSets res;
res.reserve(sets.size());
for (auto& [d, s] : sets)
res.push_back(s);
return res;
}
static double EstimateModuleSize(const BitMatrix& image, PointF a, PointF b)
{
BitMatrixCursorF cur(image, a, b - a);
cur.stepToEdge(3);
cur.turnBack();
cur.step();
assert(cur.isBlack());
auto pattern = cur.readPattern<std::array<int, 4>>();
return Reduce(pattern) / 6.0 * length(cur.d);
}
struct DimensionEstimate
{
int dim = 0;
double ms = 0;
int err = 0;
};
static DimensionEstimate EstimateDimension(const BitMatrix& image, PointF a, PointF b)
{
auto ms_a = EstimateModuleSize(image, a, b);
auto ms_b = EstimateModuleSize(image, b, a);
auto moduleSize = (ms_a + ms_b) / 2;
int dimension = std::lround(distance(a, b) / moduleSize) + 7;
int error = 1 - (dimension % 4);
return {dimension + error, moduleSize, std::abs(error)};
}
static RegressionLine TraceLine(const BitMatrix& image, PointF p, PointF d, int edge)
{
BitMatrixCursorF cur(image, p, d - p);
RegressionLine line;
line.setDirectionInward(cur.back());
cur.stepToEdge(edge);
if (edge == 3) {
// collect points inside the black line -> go one step back
cur.turnBack();
cur.step();
}
for (auto dir : {Direction::LEFT, Direction::RIGHT}) {
auto c = BitMatrixCursorI(image, PointI(cur.p), PointI(mainDirection(cur.direction(dir))));
// if cur.d is near diagonal, it could be c.p is at a corner, i.e. c is not currently at an edge and hence,
// stepAlongEdge() would fail. Going either a step forward or backward should do the trick.
if (!c.edgeAt(dir)) {
c.step();
if (!c.edgeAt(dir)) {
c.step(-2);
if (!c.edgeAt(dir))
return {};
}
}
auto stepCount = static_cast<int>(maxAbsComponent(cur.p - p));
do {
line.add(centered(c.p));
} while (--stepCount > 0 && c.stepAlongEdge(dir, true));
}
line.evaluate(1.0);
for (auto p : line.points())
log(p, 2);
return line;
}
static DetectorResult SampleAtFinderPatternSet(const BitMatrix& image, const FinderPatternSet& fp)
{
auto top = EstimateDimension(image, fp.tl, fp.tr);
auto left = EstimateDimension(image, fp.tl, fp.bl);
auto best = top.err < left.err ? top : left;
int dimension = best.dim;
int moduleSize = static_cast<int>(best.ms + 1);
// generate 4 lines: outer and inner edge of the 1 module wide black line between the two outer and the inner
// (tl) finder pattern
auto bl2 = TraceLine(image, fp.bl, fp.tl, 2);
auto bl3 = TraceLine(image, fp.bl, fp.tl, 3);
auto tr2 = TraceLine(image, fp.tr, fp.tl, 2);
auto tr3 = TraceLine(image, fp.tr, fp.tl, 3);
auto quad = Rectangle(dimension, dimension, 3.5);
PointF br = fp.tr - fp.tl + fp.bl;
if (bl2.isValid() && tr2.isValid() && bl3.isValid() && tr3.isValid()) {
// intersect both outer and inner line pairs and take the center point between the two intersection points
br = (intersect(bl2, tr2) + intersect(bl3, tr3)) / 2;
// if the estimated alignment pattern position is outside of the image, stop here
if (!image.isIn(PointI(br), 3 * moduleSize))
return {};
log(br, 3);
quad[2] = quad[2] - PointF(3, 3);
// Everything except version 1 (21 modules) has an alignment pattern
if (dimension > 21) {
// in case we landed outside of the central black module of the alignment pattern, use the center
// of the next best circle (either outer or inner edge of the white part of the alignment pattern)
auto br2 = CenterOfRing(image, PointI(br), moduleSize * 4, 1, false).value_or(br);
// if we did not land on a black pixel or the concentric pattern finder fails,
// leave the intersection of the lines as the best guess
if (image.get(br2))
br = LocateConcentricPattern<true>(image, FixedPattern<3, 3>{1, 1, 1}, br2, moduleSize * 3)
.value_or(ConcentricPattern{br});
}
}
return SampleGrid(image, dimension, dimension, {quad, {fp.tl, fp.tr, br, fp.bl}});
}
/**
* This method detects a code in a "pure" image -- that is, pure monochrome image
* which contains only an unrotated, unskewed, image of a code, with some white border
* around it. This is a specialized method that works exceptionally fast in this special
* case.
*/
static DetectorResult DetectPure(const BitMatrix& image)
{
const int minSize = 21; // Number of modules in the smallest QRCode (Version 1)
int left, top, width, height;
if (!image.findBoundingBox(left, top, width, height, minSize) || width != height)
return {};
// The upper-left corner must contain a finder pattern.
float moduleSize = BitMatrixCursorF(image, PointF(left, top), PointF(1, 1)).stepToEdge(5) / 7.f;
int symbolSize = std::lround(width / moduleSize);
if (symbolSize < minSize)
return {};
int right = left + width - 1;
int bottom = top + height - 1;
// Now just read off the bits (this is a crop + subsample)
return {Deflate(image, symbolSize, symbolSize, top + moduleSize / 2.f, left + moduleSize / 2.f, moduleSize),
{{left, top}, {right, top}, {right, bottom}, {left, bottom}}};
}
DetectorResult Detect(const BitMatrix& image, bool tryHarder, bool isPure)
{
#ifdef PRINT_DEBUG
LogMatrixWriter lmw(log, image, 5, "qr-log.pnm");
#endif
if (isPure)
return DetectPure(image);
auto sets = GenerateFinderPatternSets(FindFinderPatterns(image, tryHarder));
if (sets.empty())
return {};
#ifdef PRINT_DEBUG
printf("size of sets: %d\n", Size(sets));
#endif
return SampleAtFinderPatternSet(image, sets[0]);
}
} // namespace ZXing::QRCode
<commit_msg>QRCode: fix crash in DetectPure()<commit_after>/*
* Copyright 2016 Nu-book Inc.
* Copyright 2016 ZXing authors
* Copyright 2020 Axel Waggershauser
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "QRDetector.h"
#include "BitMatrix.h"
#include "BitMatrixCursor.h"
#include "ConcentricFinder.h"
#include "DetectorResult.h"
#include "GridSampler.h"
#include "LogMatrix.h"
#include "PerspectiveTransform.h"
#include "QRVersion.h"
#include "RegressionLine.h"
#include <algorithm>
#include <cmath>
#include <cstdlib>
#include <limits>
#include <map>
#include <utility>
namespace ZXing::QRCode {
static auto FindFinderPatterns(const BitMatrix& image, bool tryHarder)
{
constexpr int MIN_SKIP = 3; // 1 pixel/module times 3 modules/center
constexpr int MAX_MODULES = 20 * 4 + 17; // support up to version 20 for mobile clients
constexpr auto PATTERN = FixedPattern<5, 7>{1, 1, 3, 1, 1};
// Let's assume that the maximum version QR Code we support takes up 1/4 the height of the
// image, and then account for the center being 3 modules in size. This gives the smallest
// number of pixels the center could be, so skip this often. When trying harder, look for all
// QR versions regardless of how dense they are.
int height = image.height();
int skip = (3 * height) / (4 * MAX_MODULES);
if (skip < MIN_SKIP || tryHarder)
skip = MIN_SKIP;
std::vector<ConcentricPattern> res;
for (int y = skip - 1; y < height; y += skip) {
PatternRow row;
image.getPatternRow(y, row);
PatternView next = row;
while (next = FindLeftGuard(next, 0, PATTERN, 0.5), next.isValid()) {
PointF p(next.pixelsInFront() + next[0] + next[1] + next[2] / 2.0, y + 0.5);
// make sure p is not 'inside' an already found pattern area
if (FindIf(res, [p](const auto& old) { return distance(p, old) < old.size / 2; }) == res.end()) {
auto pattern = LocateConcentricPattern(image, PATTERN, p,
Reduce(next) * 3 / 2); // 1.5 for very skewed samples
if (pattern) {
log(*pattern, 3);
res.push_back(*pattern);
}
}
next.skipPair();
next.skipPair();
next.extend();
}
}
return res;
}
struct FinderPatternSet
{
ConcentricPattern bl, tl, tr;
};
using FinderPatternSets = std::vector<FinderPatternSet>;
/**
* @brief GenerateFinderPatternSets
* @param patterns list of ConcentricPattern objects, i.e. found finder pattern squares
* @return list of plausible finder pattern sets, sorted by decreasing plausibility
*/
static FinderPatternSets GenerateFinderPatternSets(std::vector<ConcentricPattern>&& patterns)
{
std::sort(patterns.begin(), patterns.end(), [](const auto& a, const auto& b) { return a.size < b.size; });
auto sets = std::multimap<double, FinderPatternSet>();
auto squaredDistance = [](PointF a, PointF b) { return dot((a - b), (a - b)); };
int nbPatterns = Size(patterns);
for (int i = 0; i < nbPatterns - 2; i++) {
for (int j = i + 1; j < nbPatterns - 1; j++) {
for (int k = j + 1; k < nbPatterns - 0; k++) {
const auto* a = &patterns[i];
const auto* b = &patterns[j];
const auto* c = &patterns[k];
// if the pattern sizes are too different to be part of the same symbol, skip this
// and the rest of the innermost loop (sorted list)
if (c->size > a->size * 2)
break;
// Orders the three points in an order [A,B,C] such that AB is less than AC
// and BC is less than AC, and the angle between BC and BA is less than 180 degrees.
auto distAB = squaredDistance(*a, *b);
auto distBC = squaredDistance(*b, *c);
auto distAC = squaredDistance(*a, *c);
if (distBC >= distAB && distBC >= distAC) {
std::swap(a, b);
std::swap(distBC, distAC);
} else if (distAB >= distAC && distAB >= distBC) {
std::swap(b, c);
std::swap(distAB, distAC);
}
// Estimate the module count and ignore this set if it can not result in a valid decoding
if (auto moduleCount =
(std::sqrt(distAB) + std::sqrt(distBC)) / (2 * (a->size + b->size + c->size) / (3 * 7.f)) + 7;
moduleCount < 21 * 0.9 || moduleCount > 177 * 1.05)
continue;
// a^2 + b^2 = c^2 (Pythagorean theorem), and a = b (isosceles triangle).
// Since any right triangle satisfies the formula c^2 - b^2 - a^2 = 0,
// we need to check both two equal sides separately.
// The value of |c^2 - 2 * b^2| + |c^2 - 2 * a^2| increases as dissimilarity
// from isosceles right triangle.
double d = std::abs(distAC - 2 * distAB) + std::abs(distAC - 2 * distBC);
// Use cross product to figure out whether A and C are correct or flipped.
// This asks whether BC x BA has a positive z component, which is the arrangement
// we want for A, B, C. If it's negative then swap A and C.
if (cross(*c - *b, *a - *b) < 0)
std::swap(a, c);
// arbitrarily limit the number of potential sets
if (sets.size() < 16 || sets.crbegin()->first > d) {
sets.emplace(d, FinderPatternSet{*a, *b, *c});
if (sets.size() > 16)
sets.erase(std::prev(sets.end()));
}
}
}
}
// convert from multimap to vector
FinderPatternSets res;
res.reserve(sets.size());
for (auto& [d, s] : sets)
res.push_back(s);
return res;
}
static double EstimateModuleSize(const BitMatrix& image, PointF a, PointF b)
{
BitMatrixCursorF cur(image, a, b - a);
cur.stepToEdge(3);
cur.turnBack();
cur.step();
assert(cur.isBlack());
auto pattern = cur.readPattern<std::array<int, 4>>();
return Reduce(pattern) / 6.0 * length(cur.d);
}
struct DimensionEstimate
{
int dim = 0;
double ms = 0;
int err = 0;
};
static DimensionEstimate EstimateDimension(const BitMatrix& image, PointF a, PointF b)
{
auto ms_a = EstimateModuleSize(image, a, b);
auto ms_b = EstimateModuleSize(image, b, a);
auto moduleSize = (ms_a + ms_b) / 2;
int dimension = std::lround(distance(a, b) / moduleSize) + 7;
int error = 1 - (dimension % 4);
return {dimension + error, moduleSize, std::abs(error)};
}
static RegressionLine TraceLine(const BitMatrix& image, PointF p, PointF d, int edge)
{
BitMatrixCursorF cur(image, p, d - p);
RegressionLine line;
line.setDirectionInward(cur.back());
cur.stepToEdge(edge);
if (edge == 3) {
// collect points inside the black line -> go one step back
cur.turnBack();
cur.step();
}
for (auto dir : {Direction::LEFT, Direction::RIGHT}) {
auto c = BitMatrixCursorI(image, PointI(cur.p), PointI(mainDirection(cur.direction(dir))));
// if cur.d is near diagonal, it could be c.p is at a corner, i.e. c is not currently at an edge and hence,
// stepAlongEdge() would fail. Going either a step forward or backward should do the trick.
if (!c.edgeAt(dir)) {
c.step();
if (!c.edgeAt(dir)) {
c.step(-2);
if (!c.edgeAt(dir))
return {};
}
}
auto stepCount = static_cast<int>(maxAbsComponent(cur.p - p));
do {
line.add(centered(c.p));
} while (--stepCount > 0 && c.stepAlongEdge(dir, true));
}
line.evaluate(1.0);
for (auto p : line.points())
log(p, 2);
return line;
}
static DetectorResult SampleAtFinderPatternSet(const BitMatrix& image, const FinderPatternSet& fp)
{
auto top = EstimateDimension(image, fp.tl, fp.tr);
auto left = EstimateDimension(image, fp.tl, fp.bl);
auto best = top.err < left.err ? top : left;
int dimension = best.dim;
int moduleSize = static_cast<int>(best.ms + 1);
// generate 4 lines: outer and inner edge of the 1 module wide black line between the two outer and the inner
// (tl) finder pattern
auto bl2 = TraceLine(image, fp.bl, fp.tl, 2);
auto bl3 = TraceLine(image, fp.bl, fp.tl, 3);
auto tr2 = TraceLine(image, fp.tr, fp.tl, 2);
auto tr3 = TraceLine(image, fp.tr, fp.tl, 3);
auto quad = Rectangle(dimension, dimension, 3.5);
PointF br = fp.tr - fp.tl + fp.bl;
if (bl2.isValid() && tr2.isValid() && bl3.isValid() && tr3.isValid()) {
// intersect both outer and inner line pairs and take the center point between the two intersection points
br = (intersect(bl2, tr2) + intersect(bl3, tr3)) / 2;
// if the estimated alignment pattern position is outside of the image, stop here
if (!image.isIn(PointI(br), 3 * moduleSize))
return {};
log(br, 3);
quad[2] = quad[2] - PointF(3, 3);
// Everything except version 1 (21 modules) has an alignment pattern
if (dimension > 21) {
// in case we landed outside of the central black module of the alignment pattern, use the center
// of the next best circle (either outer or inner edge of the white part of the alignment pattern)
auto br2 = CenterOfRing(image, PointI(br), moduleSize * 4, 1, false).value_or(br);
// if we did not land on a black pixel or the concentric pattern finder fails,
// leave the intersection of the lines as the best guess
if (image.get(br2))
br = LocateConcentricPattern<true>(image, FixedPattern<3, 3>{1, 1, 1}, br2, moduleSize * 3)
.value_or(ConcentricPattern{br});
}
}
return SampleGrid(image, dimension, dimension, {quad, {fp.tl, fp.tr, br, fp.bl}});
}
/**
* This method detects a code in a "pure" image -- that is, pure monochrome image
* which contains only an unrotated, unskewed, image of a code, with some white border
* around it. This is a specialized method that works exceptionally fast in this special
* case.
*/
static DetectorResult DetectPure(const BitMatrix& image)
{
const int minSize = 21; // Number of modules in the smallest QRCode (Version 1)
int left, top, width, height;
if (!image.findBoundingBox(left, top, width, height, minSize) || width != height)
return {};
// The upper-left corner must contain a finder pattern.
float moduleSize = BitMatrixCursorF(image, PointF(left, top), PointF(1, 1)).stepToEdge(5) / 7.f;
int symbolSize = std::lround(width / moduleSize);
if (symbolSize < minSize || !image.isIn(PointF{left + moduleSize / 2 + (symbolSize - 1) * moduleSize,
top + moduleSize / 2 + (symbolSize - 1) * moduleSize}))
return {};
int right = left + width - 1;
int bottom = top + height - 1;
// Now just read off the bits (this is a crop + subsample)
return {Deflate(image, symbolSize, symbolSize, top + moduleSize / 2.f, left + moduleSize / 2.f, moduleSize),
{{left, top}, {right, top}, {right, bottom}, {left, bottom}}};
}
DetectorResult Detect(const BitMatrix& image, bool tryHarder, bool isPure)
{
#ifdef PRINT_DEBUG
LogMatrixWriter lmw(log, image, 5, "qr-log.pnm");
#endif
if (isPure)
return DetectPure(image);
auto sets = GenerateFinderPatternSets(FindFinderPatterns(image, tryHarder));
if (sets.empty())
return {};
#ifdef PRINT_DEBUG
printf("size of sets: %d\n", Size(sets));
#endif
return SampleAtFinderPatternSet(image, sets[0]);
}
} // namespace ZXing::QRCode
<|endoftext|> |
<commit_before>/** \brief MARC grep the Next Generation.
* \author Dr. Johannes Ruscheinski (johannes.ruscheinski@uni-tuebingen.de)
*
* \copyright 2019 Universitätsbibliothek Tübingen. All rights reserved.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU Affero General Public License as
* published by the Free Software Foundation, either version 3 of the
* License, or (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Affero General Public License for more details.
*
* You should have received a copy of the GNU Affero General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <iostream>
#include <cstdlib>
#include "Compiler.h"
#include "MARC.h"
#include "StringUtil.h"
#include "util.h"
namespace {
[[noreturn]] void Usage() {
::Usage("--query=query [--output-format=output_format] marc_file1 [marc_file2 .. marc_fileN]\n"
"Queries have the following syntax:\n"
"expression → term {OR term}\n"
"term → factor {AND factor}\n"
"factor → id\n"
"factor → NOT factor\n"
"factor → '(' expression ')'\n"
);
std::exit(EXIT_FAILURE);
}
enum TokenType { AND, OR, NOT, STRING_CONST, FUNC_CALL, OPEN_PAREN, CLOSE_PAREN, COMMA, ERROR, END_OF_QUERY };
class Tokenizer {
struct FunctionDesc {
std::string name_;
unsigned argument_count_;
};
std::string::const_iterator next_ch_;
const std::string::const_iterator end_;
bool pushed_back_;
TokenType last_token_;
std::string last_error_message_;
std::string last_string_;
std::string last_function_name_;
const static std::vector<FunctionDesc> function_descriptions_;
public:
explicit Tokenizer(const std:: string &query): next_ch_(query.cbegin()), end_(query.cend()), pushed_back_(false) { }
TokenType getNextToken();
void ungetLastToken();
inline const std::string &getLastErrorMessage() const { return last_error_message_; }
inline const std::string &getLastString() const { return last_string_; }
inline const std::string &getLastFunctionName() const { return last_function_name_; }
static std::string TokenTypeToString(const TokenType token);
private:
TokenType parseStringConstant();
bool isKnownFunctionName(const std::string &name_candidate) const;
};
const std::vector<Tokenizer::FunctionDesc> Tokenizer::function_descriptions_{ { "HasField", 1 }, { "HasSubfield", 2} };
TokenType Tokenizer::getNextToken() {
if (pushed_back_) {
pushed_back_ = false;
return last_token_;
}
// Skip over spaces:
while (next_ch_ != end_ and *next_ch_ == ' ')
++next_ch_;
if (next_ch_ == end_)
return last_token_ = END_OF_QUERY;
if (*next_ch_ == '"')
return last_token_ = parseStringConstant();
if (*next_ch_ == ',') {
++next_ch_;
return last_token_ = COMMA;
}
if (*next_ch_ == '(') {
++next_ch_;
return last_token_ = OPEN_PAREN;
}
if (*next_ch_ == ')') {
++next_ch_;
return last_token_ = CLOSE_PAREN;
}
if (unlikely(not StringUtil::IsAsciiLetter(*next_ch_))) {
last_error_message_ = "expected ASCII letter!";
return ERROR;
}
std::string id;
while (next_ch_ != end_ and StringUtil::IsAsciiLetter(*next_ch_))
id += *next_ch_;
if (id == "AND")
return last_token_ = AND;
if (id == "OR")
return last_token_ = OR;
if (id == "NOT")
return last_token_ = NOT;
if (isKnownFunctionName(id)) {
last_function_name_ = id;
return last_token_ = FUNC_CALL;
}
last_error_message_ = "unknown function name \"" + id + "\"!";
return ERROR;
}
void Tokenizer::ungetLastToken() {
if (unlikely(pushed_back_))
LOG_ERROR("can't push back two tokens in a row!");
pushed_back_ = true;
}
TokenType Tokenizer::parseStringConstant() {
last_string_.clear();
bool escaped(false);
for (/* Intentionally empty! */; next_ch_ != end_; ++next_ch_) {
if (escaped) {
escaped = false;
last_string_ += *next_ch_;
} else if (*next_ch_ == '"') {
++next_ch_;
return STRING_CONST;
} else if (*next_ch_ == '\\')
escaped = true;
else
last_string_ += *next_ch_;
}
last_error_message_ = "unterminated string constant!";
return ERROR;
}
bool Tokenizer::isKnownFunctionName(const std::string &name_candidate) const {
for (const auto &function_description : function_descriptions_) {
if (function_description.name_ == name_candidate)
return true;
}
return false;
}
std::string Tokenizer::TokenTypeToString(const TokenType token) {
switch (token) {
case AND:
return "AND";
case OR:
return "OR";
case NOT:
return "NOT";
case STRING_CONST:
return "string constant";
case FUNC_CALL:
return "function call";
case OPEN_PAREN:
return "(";
case CLOSE_PAREN:
return ")";
case COMMA:
return ",";
case ERROR:
return "unexpected input";
case END_OF_QUERY:
return "end-of-query";
}
}
class Query {
Tokenizer tokenizer_;
public:
explicit Query(const std:: string &query);
bool matched(const MARC::Record &record) const;
private:
void ParseExpression();
void ParseTerm();
void ParseFactor();
};
Query::Query(const std:: string &query): tokenizer_(query) {
ParseExpression();
}
bool Query::matched(const MARC::Record &/*record*/) const {
return false;
}
void Query::ParseExpression() {
ParseTerm();
TokenType token(tokenizer_.getNextToken());
while (token == OR) {
ParseTerm();
token = tokenizer_.getNextToken();
}
tokenizer_.ungetLastToken();
}
void Query::ParseTerm() {
ParseFactor();
TokenType token(tokenizer_.getNextToken());
while (token == OR) {
ParseFactor();
token = tokenizer_.getNextToken();
}
tokenizer_.ungetLastToken();
}
void Query::ParseFactor() {
TokenType token(tokenizer_.getNextToken());
if (token == STRING_CONST)
return;
if (token == NOT) {
ParseFactor();
return;
}
if (token != OPEN_PAREN)
throw std::runtime_error("opening parenthesis, NOT or string constant expected found " + Tokenizer::TokenTypeToString(token)
+ "instead!");
ParseExpression();
token = tokenizer_.getNextToken();
if (token != CLOSE_PAREN)
throw std::runtime_error("closing parenthesis after expression expected, found " + Tokenizer::TokenTypeToString(token) + "instead!");
}
void ProcessRecords(const Query &query, MARC::Reader * const marc_reader) {
unsigned record_count(0), matched_count(0);
while (const MARC::Record record = marc_reader->read()) {
++record_count;
if (not query.matched(record))
continue;
++matched_count;
}
std::cerr << "Matched " << matched_count << " of " << record_count << " records.\n";
}
} // unnamed namespace
int Main(int argc, char *argv[]) {
if (argc < 3)
Usage();
if (not StringUtil::StartsWith(argv[1], "--query="))
LOG_ERROR("missing --query=...!");
const std::string query_str(argv[1] + __builtin_strlen("--query="));
Query query(query_str);
if (argc < 3)
Usage();
for (int arg_no(1); arg_no < argc; ++arg_no) {
auto marc_reader(MARC::Reader::Factory(argv[1]));
ProcessRecords(query, marc_reader.get());
}
return EXIT_SUCCESS;
}
<commit_msg>Fixed ParseTerm.<commit_after>/** \brief MARC grep the Next Generation.
* \author Dr. Johannes Ruscheinski (johannes.ruscheinski@uni-tuebingen.de)
*
* \copyright 2019 Universitätsbibliothek Tübingen. All rights reserved.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU Affero General Public License as
* published by the Free Software Foundation, either version 3 of the
* License, or (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Affero General Public License for more details.
*
* You should have received a copy of the GNU Affero General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <iostream>
#include <cstdlib>
#include "Compiler.h"
#include "MARC.h"
#include "StringUtil.h"
#include "util.h"
namespace {
[[noreturn]] void Usage() {
::Usage("--query=query [--output-format=output_format] marc_file1 [marc_file2 .. marc_fileN]\n"
"Queries have the following syntax:\n"
"expression → term {OR term}\n"
"term → factor {AND factor}\n"
"factor → id\n"
"factor → NOT factor\n"
"factor → '(' expression ')'\n"
);
std::exit(EXIT_FAILURE);
}
enum TokenType { AND, OR, NOT, STRING_CONST, FUNC_CALL, OPEN_PAREN, CLOSE_PAREN, COMMA, ERROR, END_OF_QUERY };
class Tokenizer {
struct FunctionDesc {
std::string name_;
unsigned argument_count_;
};
std::string::const_iterator next_ch_;
const std::string::const_iterator end_;
bool pushed_back_;
TokenType last_token_;
std::string last_error_message_;
std::string last_string_;
std::string last_function_name_;
const static std::vector<FunctionDesc> function_descriptions_;
public:
explicit Tokenizer(const std:: string &query): next_ch_(query.cbegin()), end_(query.cend()), pushed_back_(false) { }
TokenType getNextToken();
void ungetLastToken();
inline const std::string &getLastErrorMessage() const { return last_error_message_; }
inline const std::string &getLastString() const { return last_string_; }
inline const std::string &getLastFunctionName() const { return last_function_name_; }
static std::string TokenTypeToString(const TokenType token);
private:
TokenType parseStringConstant();
bool isKnownFunctionName(const std::string &name_candidate) const;
};
const std::vector<Tokenizer::FunctionDesc> Tokenizer::function_descriptions_{ { "HasField", 1 }, { "HasSubfield", 2} };
TokenType Tokenizer::getNextToken() {
if (pushed_back_) {
pushed_back_ = false;
return last_token_;
}
// Skip over spaces:
while (next_ch_ != end_ and *next_ch_ == ' ')
++next_ch_;
if (next_ch_ == end_)
return last_token_ = END_OF_QUERY;
if (*next_ch_ == '"')
return last_token_ = parseStringConstant();
if (*next_ch_ == ',') {
++next_ch_;
return last_token_ = COMMA;
}
if (*next_ch_ == '(') {
++next_ch_;
return last_token_ = OPEN_PAREN;
}
if (*next_ch_ == ')') {
++next_ch_;
return last_token_ = CLOSE_PAREN;
}
if (unlikely(not StringUtil::IsAsciiLetter(*next_ch_))) {
last_error_message_ = "expected ASCII letter!";
return ERROR;
}
std::string id;
while (next_ch_ != end_ and StringUtil::IsAsciiLetter(*next_ch_))
id += *next_ch_;
if (id == "AND")
return last_token_ = AND;
if (id == "OR")
return last_token_ = OR;
if (id == "NOT")
return last_token_ = NOT;
if (isKnownFunctionName(id)) {
last_function_name_ = id;
return last_token_ = FUNC_CALL;
}
last_error_message_ = "unknown function name \"" + id + "\"!";
return ERROR;
}
void Tokenizer::ungetLastToken() {
if (unlikely(pushed_back_))
LOG_ERROR("can't push back two tokens in a row!");
pushed_back_ = true;
}
TokenType Tokenizer::parseStringConstant() {
last_string_.clear();
bool escaped(false);
for (/* Intentionally empty! */; next_ch_ != end_; ++next_ch_) {
if (escaped) {
escaped = false;
last_string_ += *next_ch_;
} else if (*next_ch_ == '"') {
++next_ch_;
return STRING_CONST;
} else if (*next_ch_ == '\\')
escaped = true;
else
last_string_ += *next_ch_;
}
last_error_message_ = "unterminated string constant!";
return ERROR;
}
bool Tokenizer::isKnownFunctionName(const std::string &name_candidate) const {
for (const auto &function_description : function_descriptions_) {
if (function_description.name_ == name_candidate)
return true;
}
return false;
}
std::string Tokenizer::TokenTypeToString(const TokenType token) {
switch (token) {
case AND:
return "AND";
case OR:
return "OR";
case NOT:
return "NOT";
case STRING_CONST:
return "string constant";
case FUNC_CALL:
return "function call";
case OPEN_PAREN:
return "(";
case CLOSE_PAREN:
return ")";
case COMMA:
return ",";
case ERROR:
return "unexpected input";
case END_OF_QUERY:
return "end-of-query";
}
}
class Query {
Tokenizer tokenizer_;
public:
explicit Query(const std:: string &query);
bool matched(const MARC::Record &record) const;
private:
void ParseExpression();
void ParseTerm();
void ParseFactor();
};
Query::Query(const std:: string &query): tokenizer_(query) {
ParseExpression();
}
bool Query::matched(const MARC::Record &/*record*/) const {
return false;
}
void Query::ParseExpression() {
ParseTerm();
TokenType token(tokenizer_.getNextToken());
while (token == AND) {
ParseTerm();
token = tokenizer_.getNextToken();
}
tokenizer_.ungetLastToken();
}
void Query::ParseTerm() {
ParseFactor();
TokenType token(tokenizer_.getNextToken());
while (token == OR) {
ParseFactor();
token = tokenizer_.getNextToken();
}
tokenizer_.ungetLastToken();
}
void Query::ParseFactor() {
TokenType token(tokenizer_.getNextToken());
if (token == STRING_CONST)
return;
if (token == NOT) {
ParseFactor();
return;
}
if (token != OPEN_PAREN)
throw std::runtime_error("opening parenthesis, NOT or string constant expected found " + Tokenizer::TokenTypeToString(token)
+ "instead!");
ParseExpression();
token = tokenizer_.getNextToken();
if (token != CLOSE_PAREN)
throw std::runtime_error("closing parenthesis after expression expected, found " + Tokenizer::TokenTypeToString(token) + "instead!");
}
void ProcessRecords(const Query &query, MARC::Reader * const marc_reader) {
unsigned record_count(0), matched_count(0);
while (const MARC::Record record = marc_reader->read()) {
++record_count;
if (not query.matched(record))
continue;
++matched_count;
}
std::cerr << "Matched " << matched_count << " of " << record_count << " records.\n";
}
} // unnamed namespace
int Main(int argc, char *argv[]) {
if (argc < 3)
Usage();
if (not StringUtil::StartsWith(argv[1], "--query="))
LOG_ERROR("missing --query=...!");
const std::string query_str(argv[1] + __builtin_strlen("--query="));
Query query(query_str);
if (argc < 3)
Usage();
for (int arg_no(1); arg_no < argc; ++arg_no) {
auto marc_reader(MARC::Reader::Factory(argv[1]));
ProcessRecords(query, marc_reader.get());
}
return EXIT_SUCCESS;
}
<|endoftext|> |
<commit_before>/*************************************************************************
*
* $RCSfile: xmllib_import.cxx,v $
*
* $Revision: 1.7 $
*
* last change: $Author: obo $ $Date: 2003-09-04 09:20:09 $
*
* The Contents of this file are made available subject to the terms of
* either of the following licenses
*
* - GNU Lesser General Public License Version 2.1
* - Sun Industry Standards Source License Version 1.1
*
* Sun Microsystems Inc., October, 2000
*
* GNU Lesser General Public License Version 2.1
* =============================================
* Copyright 2000 by Sun Microsystems, Inc.
* 901 San Antonio Road, Palo Alto, CA 94303, USA
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License version 2.1, as published by the Free Software Foundation.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307 USA
*
*
* Sun Industry Standards Source License Version 1.1
* =================================================
* The contents of this file are subject to the Sun Industry Standards
* Source License Version 1.1 (the "License"); You may not use this file
* except in compliance with the License. You may obtain a copy of the
* License at http://www.openoffice.org/license.html.
*
* Software provided under this License is provided on an "AS IS" basis,
* WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING,
* WITHOUT LIMITATION, WARRANTIES THAT THE SOFTWARE IS FREE OF DEFECTS,
* MERCHANTABLE, FIT FOR A PARTICULAR PURPOSE, OR NON-INFRINGING.
* See the License for the specific provisions governing your rights and
* obligations concerning the Software.
*
* The Initial Developer of the Original Code is: Sun Microsystems, Inc.
*
* Copyright: 2000 by Sun Microsystems, Inc.
*
* All Rights Reserved.
*
* Contributor(s): _______________________________________
*
*
************************************************************************/
#include "imp_share.hxx"
#include <osl/diagnose.h>
#include <rtl/ustrbuf.hxx>
#include <xmlscript/xml_import.hxx>
#include <comphelper/processfactory.hxx>
namespace xmlscript
{
//##################################################################################################
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibElementBase::getParent()
throw (RuntimeException)
{
return static_cast< xml::input::XElement * >( _pParent );
}
//__________________________________________________________________________________________________
OUString LibElementBase::getLocalName()
throw (RuntimeException)
{
return _aLocalName;
}
//__________________________________________________________________________________________________
sal_Int32 LibElementBase::getUid()
throw (RuntimeException)
{
return _pImport->XMLNS_LIBRARY_UID;
}
//__________________________________________________________________________________________________
Reference< xml::input::XAttributes > LibElementBase::getAttributes()
throw (RuntimeException)
{
return _xAttributes;
}
//__________________________________________________________________________________________________
void LibElementBase::ignorableWhitespace(
OUString const & rWhitespaces )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibElementBase::characters( OUString const & rChars )
throw (xml::sax::SAXException, RuntimeException)
{
// not used, all characters ignored
}
//__________________________________________________________________________________________________
void LibElementBase::processingInstruction(
OUString const & rTarget, OUString const & rData )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibElementBase::endElement()
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibElementBase::startChildElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("unexpected element!") ),
Reference< XInterface >(), Any() );
}
//__________________________________________________________________________________________________
LibElementBase::LibElementBase(
OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes,
LibElementBase * pParent, LibraryImport * pImport )
SAL_THROW( () )
: _pImport( pImport )
, _pParent( pParent )
, _aLocalName( rLocalName )
, _xAttributes( xAttributes )
{
_pImport->acquire();
if (_pParent)
{
_pParent->acquire();
}
}
//__________________________________________________________________________________________________
LibElementBase::~LibElementBase()
SAL_THROW( () )
{
_pImport->release();
if (_pParent)
{
_pParent->release();
}
#if OSL_DEBUG_LEVEL > 1
OString aStr( OUStringToOString( _aLocalName, RTL_TEXTENCODING_ASCII_US ) );
OSL_TRACE( "LibElementBase::~LibElementBase(): %s\n", aStr.getStr() );
#endif
}
//##################################################################################################
// XRoot
//______________________________________________________________________________
void LibraryImport::startDocument(
Reference< container::XNameAccess > const & xUidMapping )
throw (xml::sax::SAXException, RuntimeException)
{
if (!(xUidMapping->getByName( OUSTR(XMLNS_LIBRARY_URI) ) >>=
XMLNS_LIBRARY_UID) ||
!(xUidMapping->getByName( OUSTR(XMLNS_XLINK_URI) ) >>=
XMLNS_XLINK_UID))
{
throw xml::sax::SAXException(
OUSTR("cannot get uids!"),
Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
void LibraryImport::endDocument()
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibraryImport::processingInstruction(
OUString const & rTarget, OUString const & rData )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibraryImport::setDocumentLocator(
Reference< xml::sax::XLocator > const & xLocator )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibraryImport::startRootElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
if (XMLNS_LIBRARY_UID != nUid)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal namespace!") ),
Reference< XInterface >(), Any() );
}
else if (mpLibArray && rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("libraries") ))
{
return new LibrariesElement( rLocalName, xAttributes, 0, this );
}
else if (mpLibDesc && rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("library") ))
{
LibDescriptor& aDesc = *mpLibDesc;
aDesc.bLink = aDesc.bReadOnly = aDesc.bPasswordProtected = sal_False;
aDesc.aName = xAttributes->getValueByUidName(
XMLNS_LIBRARY_UID, OUString( RTL_CONSTASCII_USTRINGPARAM("name") ) );
getBoolAttr(
&aDesc.bReadOnly,
OUString( RTL_CONSTASCII_USTRINGPARAM("readonly") ), xAttributes,
XMLNS_LIBRARY_UID );
getBoolAttr(
&aDesc.bPasswordProtected,
OUString( RTL_CONSTASCII_USTRINGPARAM("passwordprotected") ),
xAttributes, XMLNS_LIBRARY_UID );
return new LibraryElement( rLocalName, xAttributes, 0, this );
}
else
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal root element (expected libraries) given: ") ) +
rLocalName, Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
LibraryImport::~LibraryImport()
SAL_THROW( () )
{
#if OSL_DEBUG_LEVEL > 1
OSL_TRACE( "LibraryImport::~LibraryImport().\n" );
#endif
}
//##################################################################################################
// libraries
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibrariesElement::startChildElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
if (_pImport->XMLNS_LIBRARY_UID != nUid)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal namespace!") ),
Reference< XInterface >(), Any() );
}
// library
else if (rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("library") ))
{
LibDescriptor aDesc;
aDesc.bLink = aDesc.bReadOnly = aDesc.bPasswordProtected = sal_False;
aDesc.aName = xAttributes->getValueByUidName(
_pImport->XMLNS_LIBRARY_UID,
OUString( RTL_CONSTASCII_USTRINGPARAM("name") ) );
aDesc.aStorageURL = xAttributes->getValueByUidName(
_pImport->XMLNS_XLINK_UID,
OUString( RTL_CONSTASCII_USTRINGPARAM("href") ) );
getBoolAttr(
&aDesc.bLink,
OUString( RTL_CONSTASCII_USTRINGPARAM("link") ),
xAttributes, _pImport->XMLNS_LIBRARY_UID );
getBoolAttr(
&aDesc.bReadOnly,
OUString( RTL_CONSTASCII_USTRINGPARAM("readonly") ),
xAttributes, _pImport->XMLNS_LIBRARY_UID );
getBoolAttr(
&aDesc.bPasswordProtected,
OUString( RTL_CONSTASCII_USTRINGPARAM("passwordprotected") ),
xAttributes, _pImport->XMLNS_LIBRARY_UID );
mLibDescriptors.push_back( aDesc );
return new LibraryElement( rLocalName, xAttributes, this, _pImport );
}
else
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("expected styles ot bulletinboard element!") ),
Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
void LibrariesElement::endElement()
throw (xml::sax::SAXException, RuntimeException)
{
sal_Int32 nLibCount = _pImport->mpLibArray->mnLibCount = (sal_Int32)mLibDescriptors.size();
_pImport->mpLibArray->mpLibs = new LibDescriptor[ nLibCount ];
for( sal_Int32 i = 0 ; i < nLibCount ; i++ )
{
const LibDescriptor& rLib = mLibDescriptors[i];
_pImport->mpLibArray->mpLibs[i] = rLib;
}
}
// library
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibraryElement::startChildElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
if (_pImport->XMLNS_LIBRARY_UID != nUid)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal namespace!") ),
Reference< XInterface >(), Any() );
}
// library
else if (rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("element") ))
{
OUString aValue( xAttributes->getValueByUidName(
_pImport->XMLNS_LIBRARY_UID,
OUString( RTL_CONSTASCII_USTRINGPARAM("name") ) ) );
if (aValue.getLength())
mElements.push_back( aValue );
return new LibElementBase( rLocalName, xAttributes, this, _pImport );
}
else
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("expected styles ot bulletinboard element!") ),
Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
void LibraryElement::endElement()
throw (xml::sax::SAXException, RuntimeException)
{
sal_Int32 nElementCount = mElements.size();
Sequence< OUString > aElementNames( nElementCount );
OUString* pElementNames = aElementNames.getArray();
for( sal_Int32 i = 0 ; i < nElementCount ; i++ )
pElementNames[i] = mElements[i];
LibDescriptor* pLib = _pImport->mpLibDesc;
if( !pLib )
pLib = &static_cast< LibrariesElement* >( _pParent )->mLibDescriptors.back();
pLib->aElementNames = aElementNames;
}
//##################################################################################################
SAL_DLLEXPORT Reference< ::com::sun::star::xml::sax::XDocumentHandler >
SAL_CALL importLibraryContainer( LibDescriptorArray* pLibArray )
SAL_THROW( (Exception) )
{
return ::xmlscript::createDocumentHandler(
static_cast< xml::input::XRoot * >( new LibraryImport( pLibArray ) ) );
}
//##################################################################################################
SAL_DLLEXPORT ::com::sun::star::uno::Reference< ::com::sun::star::xml::sax::XDocumentHandler >
SAL_CALL importLibrary( LibDescriptor& rLib )
SAL_THROW( (::com::sun::star::uno::Exception) )
{
return ::xmlscript::createDocumentHandler(
static_cast< xml::input::XRoot * >( new LibraryImport( &rLib ) ) );
}
//##################################################################################################
LibDescriptorArray::LibDescriptorArray( sal_Int32 nLibCount )
{
mnLibCount = nLibCount;
mpLibs = new LibDescriptor[ mnLibCount ];
}
LibDescriptorArray::~LibDescriptorArray()
{
delete[] mpLibs;
}
};
<commit_msg>INTEGRATION: CWS jl5vba (1.7.14); FILE MERGED 2004/01/21 14:36:26 ab 1.7.14.1: #111934# Merge to src680, #110009# Added library preload flag<commit_after>/*************************************************************************
*
* $RCSfile: xmllib_import.cxx,v $
*
* $Revision: 1.8 $
*
* last change: $Author: obo $ $Date: 2004-03-17 13:42:51 $
*
* The Contents of this file are made available subject to the terms of
* either of the following licenses
*
* - GNU Lesser General Public License Version 2.1
* - Sun Industry Standards Source License Version 1.1
*
* Sun Microsystems Inc., October, 2000
*
* GNU Lesser General Public License Version 2.1
* =============================================
* Copyright 2000 by Sun Microsystems, Inc.
* 901 San Antonio Road, Palo Alto, CA 94303, USA
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License version 2.1, as published by the Free Software Foundation.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307 USA
*
*
* Sun Industry Standards Source License Version 1.1
* =================================================
* The contents of this file are subject to the Sun Industry Standards
* Source License Version 1.1 (the "License"); You may not use this file
* except in compliance with the License. You may obtain a copy of the
* License at http://www.openoffice.org/license.html.
*
* Software provided under this License is provided on an "AS IS" basis,
* WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING,
* WITHOUT LIMITATION, WARRANTIES THAT THE SOFTWARE IS FREE OF DEFECTS,
* MERCHANTABLE, FIT FOR A PARTICULAR PURPOSE, OR NON-INFRINGING.
* See the License for the specific provisions governing your rights and
* obligations concerning the Software.
*
* The Initial Developer of the Original Code is: Sun Microsystems, Inc.
*
* Copyright: 2000 by Sun Microsystems, Inc.
*
* All Rights Reserved.
*
* Contributor(s): _______________________________________
*
*
************************************************************************/
#include "imp_share.hxx"
#include <osl/diagnose.h>
#include <rtl/ustrbuf.hxx>
#include <xmlscript/xml_import.hxx>
#include <comphelper/processfactory.hxx>
namespace xmlscript
{
//##################################################################################################
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibElementBase::getParent()
throw (RuntimeException)
{
return static_cast< xml::input::XElement * >( _pParent );
}
//__________________________________________________________________________________________________
OUString LibElementBase::getLocalName()
throw (RuntimeException)
{
return _aLocalName;
}
//__________________________________________________________________________________________________
sal_Int32 LibElementBase::getUid()
throw (RuntimeException)
{
return _pImport->XMLNS_LIBRARY_UID;
}
//__________________________________________________________________________________________________
Reference< xml::input::XAttributes > LibElementBase::getAttributes()
throw (RuntimeException)
{
return _xAttributes;
}
//__________________________________________________________________________________________________
void LibElementBase::ignorableWhitespace(
OUString const & rWhitespaces )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibElementBase::characters( OUString const & rChars )
throw (xml::sax::SAXException, RuntimeException)
{
// not used, all characters ignored
}
//__________________________________________________________________________________________________
void LibElementBase::processingInstruction(
OUString const & rTarget, OUString const & rData )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibElementBase::endElement()
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibElementBase::startChildElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("unexpected element!") ),
Reference< XInterface >(), Any() );
}
//__________________________________________________________________________________________________
LibElementBase::LibElementBase(
OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes,
LibElementBase * pParent, LibraryImport * pImport )
SAL_THROW( () )
: _pImport( pImport )
, _pParent( pParent )
, _aLocalName( rLocalName )
, _xAttributes( xAttributes )
{
_pImport->acquire();
if (_pParent)
{
_pParent->acquire();
}
}
//__________________________________________________________________________________________________
LibElementBase::~LibElementBase()
SAL_THROW( () )
{
_pImport->release();
if (_pParent)
{
_pParent->release();
}
#if OSL_DEBUG_LEVEL > 1
OString aStr( OUStringToOString( _aLocalName, RTL_TEXTENCODING_ASCII_US ) );
OSL_TRACE( "LibElementBase::~LibElementBase(): %s\n", aStr.getStr() );
#endif
}
//##################################################################################################
// XRoot
//______________________________________________________________________________
void LibraryImport::startDocument(
Reference< container::XNameAccess > const & xUidMapping )
throw (xml::sax::SAXException, RuntimeException)
{
if (!(xUidMapping->getByName( OUSTR(XMLNS_LIBRARY_URI) ) >>=
XMLNS_LIBRARY_UID) ||
!(xUidMapping->getByName( OUSTR(XMLNS_XLINK_URI) ) >>=
XMLNS_XLINK_UID))
{
throw xml::sax::SAXException(
OUSTR("cannot get uids!"),
Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
void LibraryImport::endDocument()
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibraryImport::processingInstruction(
OUString const & rTarget, OUString const & rData )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
void LibraryImport::setDocumentLocator(
Reference< xml::sax::XLocator > const & xLocator )
throw (xml::sax::SAXException, RuntimeException)
{
}
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibraryImport::startRootElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
if (XMLNS_LIBRARY_UID != nUid)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal namespace!") ),
Reference< XInterface >(), Any() );
}
else if (mpLibArray && rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("libraries") ))
{
return new LibrariesElement( rLocalName, xAttributes, 0, this );
}
else if (mpLibDesc && rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("library") ))
{
LibDescriptor& aDesc = *mpLibDesc;
aDesc.bLink = aDesc.bReadOnly = aDesc.bPasswordProtected = aDesc.bPreload = sal_False;
aDesc.aName = xAttributes->getValueByUidName(
XMLNS_LIBRARY_UID, OUString( RTL_CONSTASCII_USTRINGPARAM("name") ) );
getBoolAttr(
&aDesc.bReadOnly,
OUString( RTL_CONSTASCII_USTRINGPARAM("readonly") ), xAttributes,
XMLNS_LIBRARY_UID );
getBoolAttr(
&aDesc.bPasswordProtected,
OUString( RTL_CONSTASCII_USTRINGPARAM("passwordprotected") ),
xAttributes, XMLNS_LIBRARY_UID );
getBoolAttr(
&aDesc.bPreload,
OUString( RTL_CONSTASCII_USTRINGPARAM("preload") ),
xAttributes, XMLNS_LIBRARY_UID );
return new LibraryElement( rLocalName, xAttributes, 0, this );
}
else
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal root element (expected libraries) given: ") ) +
rLocalName, Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
LibraryImport::~LibraryImport()
SAL_THROW( () )
{
#if OSL_DEBUG_LEVEL > 1
OSL_TRACE( "LibraryImport::~LibraryImport().\n" );
#endif
}
//##################################################################################################
// libraries
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibrariesElement::startChildElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
if (_pImport->XMLNS_LIBRARY_UID != nUid)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal namespace!") ),
Reference< XInterface >(), Any() );
}
// library
else if (rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("library") ))
{
LibDescriptor aDesc;
aDesc.bLink = aDesc.bReadOnly = aDesc.bPasswordProtected = aDesc.bPreload = sal_False;
aDesc.aName = xAttributes->getValueByUidName(
_pImport->XMLNS_LIBRARY_UID,
OUString( RTL_CONSTASCII_USTRINGPARAM("name") ) );
aDesc.aStorageURL = xAttributes->getValueByUidName(
_pImport->XMLNS_XLINK_UID,
OUString( RTL_CONSTASCII_USTRINGPARAM("href") ) );
getBoolAttr(
&aDesc.bLink,
OUString( RTL_CONSTASCII_USTRINGPARAM("link") ),
xAttributes, _pImport->XMLNS_LIBRARY_UID );
getBoolAttr(
&aDesc.bReadOnly,
OUString( RTL_CONSTASCII_USTRINGPARAM("readonly") ),
xAttributes, _pImport->XMLNS_LIBRARY_UID );
getBoolAttr(
&aDesc.bPasswordProtected,
OUString( RTL_CONSTASCII_USTRINGPARAM("passwordprotected") ),
xAttributes, _pImport->XMLNS_LIBRARY_UID );
mLibDescriptors.push_back( aDesc );
return new LibraryElement( rLocalName, xAttributes, this, _pImport );
}
else
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("expected styles ot bulletinboard element!") ),
Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
void LibrariesElement::endElement()
throw (xml::sax::SAXException, RuntimeException)
{
sal_Int32 nLibCount = _pImport->mpLibArray->mnLibCount = (sal_Int32)mLibDescriptors.size();
_pImport->mpLibArray->mpLibs = new LibDescriptor[ nLibCount ];
for( sal_Int32 i = 0 ; i < nLibCount ; i++ )
{
const LibDescriptor& rLib = mLibDescriptors[i];
_pImport->mpLibArray->mpLibs[i] = rLib;
}
}
// library
//__________________________________________________________________________________________________
Reference< xml::input::XElement > LibraryElement::startChildElement(
sal_Int32 nUid, OUString const & rLocalName,
Reference< xml::input::XAttributes > const & xAttributes )
throw (xml::sax::SAXException, RuntimeException)
{
if (_pImport->XMLNS_LIBRARY_UID != nUid)
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("illegal namespace!") ),
Reference< XInterface >(), Any() );
}
// library
else if (rLocalName.equalsAsciiL( RTL_CONSTASCII_STRINGPARAM("element") ))
{
OUString aValue( xAttributes->getValueByUidName(
_pImport->XMLNS_LIBRARY_UID,
OUString( RTL_CONSTASCII_USTRINGPARAM("name") ) ) );
if (aValue.getLength())
mElements.push_back( aValue );
return new LibElementBase( rLocalName, xAttributes, this, _pImport );
}
else
{
throw xml::sax::SAXException(
OUString( RTL_CONSTASCII_USTRINGPARAM("expected styles ot bulletinboard element!") ),
Reference< XInterface >(), Any() );
}
}
//__________________________________________________________________________________________________
void LibraryElement::endElement()
throw (xml::sax::SAXException, RuntimeException)
{
sal_Int32 nElementCount = mElements.size();
Sequence< OUString > aElementNames( nElementCount );
OUString* pElementNames = aElementNames.getArray();
for( sal_Int32 i = 0 ; i < nElementCount ; i++ )
pElementNames[i] = mElements[i];
LibDescriptor* pLib = _pImport->mpLibDesc;
if( !pLib )
pLib = &static_cast< LibrariesElement* >( _pParent )->mLibDescriptors.back();
pLib->aElementNames = aElementNames;
}
//##################################################################################################
SAL_DLLEXPORT Reference< ::com::sun::star::xml::sax::XDocumentHandler >
SAL_CALL importLibraryContainer( LibDescriptorArray* pLibArray )
SAL_THROW( (Exception) )
{
return ::xmlscript::createDocumentHandler(
static_cast< xml::input::XRoot * >( new LibraryImport( pLibArray ) ) );
}
//##################################################################################################
SAL_DLLEXPORT ::com::sun::star::uno::Reference< ::com::sun::star::xml::sax::XDocumentHandler >
SAL_CALL importLibrary( LibDescriptor& rLib )
SAL_THROW( (::com::sun::star::uno::Exception) )
{
return ::xmlscript::createDocumentHandler(
static_cast< xml::input::XRoot * >( new LibraryImport( &rLib ) ) );
}
//##################################################################################################
LibDescriptorArray::LibDescriptorArray( sal_Int32 nLibCount )
{
mnLibCount = nLibCount;
mpLibs = new LibDescriptor[ mnLibCount ];
}
LibDescriptorArray::~LibDescriptorArray()
{
delete[] mpLibs;
}
};
<|endoftext|> |
<commit_before>/*************************************************************************
*
* OpenOffice.org - a multi-platform office productivity suite
*
* $RCSfile: tp_PointGeometry.cxx,v $
*
* $Revision: 1.6 $
*
* last change: $Author: vg $ $Date: 2007-05-22 17:47:10 $
*
* The Contents of this file are made available subject to
* the terms of GNU Lesser General Public License Version 2.1.
*
*
* GNU Lesser General Public License Version 2.1
* =============================================
* Copyright 2005 by Sun Microsystems, Inc.
* 901 San Antonio Road, Palo Alto, CA 94303, USA
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License version 2.1, as published by the Free Software Foundation.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307 USA
*
************************************************************************/
// MARKER(update_precomp.py): autogen include statement, do not remove
#include "precompiled_chart2.hxx"
#include "tp_PointGeometry.hxx"
#include "TabPages.hrc"
#include "res_BarGeometry.hxx"
#include "ResId.hxx"
#include "chartview/ChartSfxItemIds.hxx"
// header for SfxInt32Item
#ifndef _SFXINTITEM_HXX
#include <svtools/intitem.hxx>
#endif
// header for class Svx3DHorizontalSegmentsItem
#ifndef _SVX3DITEMS_HXX
#include <svx/svx3ditems.hxx>
#endif
//.............................................................................
namespace chart
{
//.............................................................................
SchLayoutTabPage::SchLayoutTabPage(Window* pWindow,const SfxItemSet& rInAttrs)
: SfxTabPage(pWindow, SchResId(TP_LAYOUT), rInAttrs)
, m_pGeometryResources(0)
{
Size aPageSize( this->GetSizePixel() );
Point aPos( this->LogicToPixel( Point(6,6), MapMode(MAP_APPFONT) ) );
m_pGeometryResources = new BarGeometryResources( this );
m_pGeometryResources->SetPosPixel( aPos );
}
SchLayoutTabPage::~SchLayoutTabPage()
{
if( m_pGeometryResources )
delete m_pGeometryResources;
}
SfxTabPage* SchLayoutTabPage::Create(Window* pWindow,
const SfxItemSet& rOutAttrs)
{
return new SchLayoutTabPage(pWindow, rOutAttrs);
}
BOOL SchLayoutTabPage::FillItemSet(SfxItemSet& rOutAttrs)
{
if(m_pGeometryResources && m_pGeometryResources->GetSelectEntryCount())
{
long nShape=CHART_SHAPE3D_SQUARE;
long nSegs=32;
nShape = m_pGeometryResources->GetSelectEntryPos();
if(nShape==CHART_SHAPE3D_PYRAMID)
nSegs=4;
rOutAttrs.Put(SfxInt32Item(SCHATTR_STYLE_SHAPE,nShape));
rOutAttrs.Put(Svx3DHorizontalSegmentsItem(nSegs));
}
return TRUE;
}
void SchLayoutTabPage::Reset(const SfxItemSet& rInAttrs)
{
const SfxPoolItem *pPoolItem = NULL;
if (rInAttrs.GetItemState(SCHATTR_STYLE_SHAPE,TRUE, &pPoolItem) == SFX_ITEM_SET)
{
long nVal=((const SfxInt32Item*)pPoolItem)->GetValue();
if(m_pGeometryResources)
{
m_pGeometryResources->SelectEntryPos(static_cast<USHORT>(nVal));
m_pGeometryResources->Show( true );
}
}
}
//.............................................................................
} //namespace chart
//.............................................................................
<commit_msg>INTEGRATION: CWS changefileheader (1.6.126); FILE MERGED 2008/04/01 15:04:04 thb 1.6.126.2: #i85898# Stripping all external header guards 2008/03/28 16:43:32 rt 1.6.126.1: #i87441# Change license header to LPGL v3.<commit_after>/*************************************************************************
*
* DO NOT ALTER OR REMOVE COPYRIGHT NOTICES OR THIS FILE HEADER.
*
* Copyright 2008 by Sun Microsystems, Inc.
*
* OpenOffice.org - a multi-platform office productivity suite
*
* $RCSfile: tp_PointGeometry.cxx,v $
* $Revision: 1.7 $
*
* This file is part of OpenOffice.org.
*
* OpenOffice.org is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License version 3
* only, as published by the Free Software Foundation.
*
* OpenOffice.org is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License version 3 for more details
* (a copy is included in the LICENSE file that accompanied this code).
*
* You should have received a copy of the GNU Lesser General Public License
* version 3 along with OpenOffice.org. If not, see
* <http://www.openoffice.org/license.html>
* for a copy of the LGPLv3 License.
*
************************************************************************/
// MARKER(update_precomp.py): autogen include statement, do not remove
#include "precompiled_chart2.hxx"
#include "tp_PointGeometry.hxx"
#include "TabPages.hrc"
#include "res_BarGeometry.hxx"
#include "ResId.hxx"
#include "chartview/ChartSfxItemIds.hxx"
// header for SfxInt32Item
#include <svtools/intitem.hxx>
// header for class Svx3DHorizontalSegmentsItem
#include <svx/svx3ditems.hxx>
//.............................................................................
namespace chart
{
//.............................................................................
SchLayoutTabPage::SchLayoutTabPage(Window* pWindow,const SfxItemSet& rInAttrs)
: SfxTabPage(pWindow, SchResId(TP_LAYOUT), rInAttrs)
, m_pGeometryResources(0)
{
Size aPageSize( this->GetSizePixel() );
Point aPos( this->LogicToPixel( Point(6,6), MapMode(MAP_APPFONT) ) );
m_pGeometryResources = new BarGeometryResources( this );
m_pGeometryResources->SetPosPixel( aPos );
}
SchLayoutTabPage::~SchLayoutTabPage()
{
if( m_pGeometryResources )
delete m_pGeometryResources;
}
SfxTabPage* SchLayoutTabPage::Create(Window* pWindow,
const SfxItemSet& rOutAttrs)
{
return new SchLayoutTabPage(pWindow, rOutAttrs);
}
BOOL SchLayoutTabPage::FillItemSet(SfxItemSet& rOutAttrs)
{
if(m_pGeometryResources && m_pGeometryResources->GetSelectEntryCount())
{
long nShape=CHART_SHAPE3D_SQUARE;
long nSegs=32;
nShape = m_pGeometryResources->GetSelectEntryPos();
if(nShape==CHART_SHAPE3D_PYRAMID)
nSegs=4;
rOutAttrs.Put(SfxInt32Item(SCHATTR_STYLE_SHAPE,nShape));
rOutAttrs.Put(Svx3DHorizontalSegmentsItem(nSegs));
}
return TRUE;
}
void SchLayoutTabPage::Reset(const SfxItemSet& rInAttrs)
{
const SfxPoolItem *pPoolItem = NULL;
if (rInAttrs.GetItemState(SCHATTR_STYLE_SHAPE,TRUE, &pPoolItem) == SFX_ITEM_SET)
{
long nVal=((const SfxInt32Item*)pPoolItem)->GetValue();
if(m_pGeometryResources)
{
m_pGeometryResources->SelectEntryPos(static_cast<USHORT>(nVal));
m_pGeometryResources->Show( true );
}
}
}
//.............................................................................
} //namespace chart
//.............................................................................
<|endoftext|> |
<commit_before>/*************************************************************************
*
* OpenOffice.org - a multi-platform office productivity suite
*
* $RCSfile: _serviceregistration_view.cxx,v $
*
* $Revision: 1.3 $
*
* last change: $Author: rt $ $Date: 2007-07-25 09:06:55 $
*
* The Contents of this file are made available subject to
* the terms of GNU Lesser General Public License Version 2.1.
*
*
* GNU Lesser General Public License Version 2.1
* =============================================
* Copyright 2005 by Sun Microsystems, Inc.
* 901 San Antonio Road, Palo Alto, CA 94303, USA
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License version 2.1, as published by the Free Software Foundation.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307 USA
*
************************************************************************/
// MARKER(update_precomp.py): autogen include statement, do not remove
#include "precompiled_chart2.hxx"
#ifndef _CPPUHELPER_IMPLEMENATIONENTRY_HXX_
#include <cppuhelper/implementationentry.hxx>
#endif
#include "ChartView.hxx"
static struct ::cppu::ImplementationEntry g_entries_chart2_view[] =
{
{
::chart::ChartView::create
, ::chart::ChartView::getImplementationName_Static
, ::chart::ChartView::getSupportedServiceNames_Static
, ::cppu::createSingleComponentFactory
, 0
, 0
}
,{ 0, 0, 0, 0, 0, 0 }
};
// component exports
extern "C"
{
//==================================================================================================
void SAL_CALL component_getImplementationEnvironment(
const sal_Char ** ppEnvTypeName, uno_Environment ** /* ppEnv */ )
{
*ppEnvTypeName = CPPU_CURRENT_LANGUAGE_BINDING_NAME;
}
//==================================================================================================
sal_Bool SAL_CALL component_writeInfo(
void * pServiceManager, void * pRegistryKey )
{
return ::cppu::component_writeInfoHelper(
pServiceManager, pRegistryKey, g_entries_chart2_view );
}
//==================================================================================================
void * SAL_CALL component_getFactory(
const sal_Char * pImplName, void * pServiceManager, void * pRegistryKey )
{
return ::cppu::component_getFactoryHelper(
pImplName, pServiceManager, pRegistryKey , g_entries_chart2_view );
}
}
//=========================================================================
<commit_msg>INTEGRATION: CWS changefileheader (1.3.94); FILE MERGED 2008/04/01 15:04:30 thb 1.3.94.2: #i85898# Stripping all external header guards 2008/03/28 16:44:49 rt 1.3.94.1: #i87441# Change license header to LPGL v3.<commit_after>/*************************************************************************
*
* DO NOT ALTER OR REMOVE COPYRIGHT NOTICES OR THIS FILE HEADER.
*
* Copyright 2008 by Sun Microsystems, Inc.
*
* OpenOffice.org - a multi-platform office productivity suite
*
* $RCSfile: _serviceregistration_view.cxx,v $
* $Revision: 1.4 $
*
* This file is part of OpenOffice.org.
*
* OpenOffice.org is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License version 3
* only, as published by the Free Software Foundation.
*
* OpenOffice.org is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License version 3 for more details
* (a copy is included in the LICENSE file that accompanied this code).
*
* You should have received a copy of the GNU Lesser General Public License
* version 3 along with OpenOffice.org. If not, see
* <http://www.openoffice.org/license.html>
* for a copy of the LGPLv3 License.
*
************************************************************************/
// MARKER(update_precomp.py): autogen include statement, do not remove
#include "precompiled_chart2.hxx"
#include <cppuhelper/implementationentry.hxx>
#include "ChartView.hxx"
static struct ::cppu::ImplementationEntry g_entries_chart2_view[] =
{
{
::chart::ChartView::create
, ::chart::ChartView::getImplementationName_Static
, ::chart::ChartView::getSupportedServiceNames_Static
, ::cppu::createSingleComponentFactory
, 0
, 0
}
,{ 0, 0, 0, 0, 0, 0 }
};
// component exports
extern "C"
{
//==================================================================================================
void SAL_CALL component_getImplementationEnvironment(
const sal_Char ** ppEnvTypeName, uno_Environment ** /* ppEnv */ )
{
*ppEnvTypeName = CPPU_CURRENT_LANGUAGE_BINDING_NAME;
}
//==================================================================================================
sal_Bool SAL_CALL component_writeInfo(
void * pServiceManager, void * pRegistryKey )
{
return ::cppu::component_writeInfoHelper(
pServiceManager, pRegistryKey, g_entries_chart2_view );
}
//==================================================================================================
void * SAL_CALL component_getFactory(
const sal_Char * pImplName, void * pServiceManager, void * pRegistryKey )
{
return ::cppu::component_getFactoryHelper(
pImplName, pServiceManager, pRegistryKey , g_entries_chart2_view );
}
}
//=========================================================================
<|endoftext|> |
<commit_before>/* Copyright 2019 The TensorFlow Authors. All Rights Reserved.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
==============================================================================*/
#include <cstdint>
#include <initializer_list>
#include <memory>
#include <vector>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include "tensorflow/lite/interpreter.h"
#include "tensorflow/lite/kernels/kernel_util.h"
#include "tensorflow/lite/kernels/register.h"
#include "tensorflow/lite/kernels/test_util.h"
#include "tensorflow/lite/model.h"
namespace tflite {
namespace {
using ::testing::ElementsAreArray;
class QuantizedLSTMOpModel : public MultiOpModel {
public:
QuantizedLSTMOpModel(int numBatches, int inputSize, float weightsScale,
int32_t weightsZeroPoint, int outputSize,
std::initializer_list<uint8_t> weights,
std::initializer_list<int32_t> biases,
// If true the LTSM node will be preceded by a noop
// one (add to 0)
bool prepend_noop) {
std::vector<uint32_t> inputs;
input_size_ = inputSize;
output_size_ = outputSize;
prepend_noop_ = prepend_noop;
std::vector<int> input_shape{numBatches, inputSize};
std::vector<int> output_shape{numBatches, outputSize};
std::vector<int> weight_shape{4 * outputSize, outputSize + inputSize};
std::vector<int> state_shape{numBatches, outputSize};
std::vector<int> bias_shape{4 * outputSize};
std::vector<int> lstm_inputs;
const TensorData input_tensor_data{
TensorType_UINT8, input_shape, 0.0f, 0.0f, 1. / 128., 128};
if (prepend_noop) {
zero_input_ = AddInput(input_tensor_data);
} else {
zero_input_ = 0;
}
input_ = AddInput(input_tensor_data);
prev_output_ =
AddInput({TensorType_UINT8, output_shape, 0.0f, 0.0f, 1. / 128., 128});
// Biases and Weights have to be constant in order to allow NNAPI
// delegation
weights_ = AddConstInput<uint8_t>({TensorType_UINT8, weight_shape, 0.0f,
0.0f, weightsScale, weightsZeroPoint},
weights);
biases_ = AddConstInput<int32_t>(
{TensorType_INT32, bias_shape, 0.0f, 0.0f, weightsScale / 128, 0},
biases);
prev_cell_state_ =
AddInput({TensorType_INT16, state_shape, 0.0f, 0.0f, 1. / 2048., 0});
sum_out_ = AddOutput(input_tensor_data);
output_ =
AddOutput({TensorType_UINT8, output_shape, 0.0f, 0.0f, 1. / 128., 128});
cell_state_out_ =
AddOutput({TensorType_INT16, state_shape, 0.0f, 0.0f, 1. / 2048., 0});
output_concat_temp_ =
AddOutput({TensorType_UINT8, output_shape, 0.0f, 0.0f, 1. / 128., 128});
output_activation_temp_ =
AddOutput({TensorType_INT16, output_shape, 0.0f, 0.0f, 1. / 128., 128});
if (prepend_noop) {
AddBuiltinOp(
BuiltinOperator_ADD, BuiltinOptions_AddOptions,
CreateAddOptions(builder_, ActivationFunctionType_NONE).Union(),
{zero_input_, input_}, {sum_out_});
lstm_inputs.push_back(sum_out_);
} else {
lstm_inputs.push_back(input_);
}
lstm_inputs.push_back(prev_output_);
lstm_inputs.push_back(weights_);
lstm_inputs.push_back(biases_);
lstm_inputs.push_back(prev_cell_state_);
std::vector<int> lstm_outputs{output_, cell_state_out_, output_concat_temp_,
output_activation_temp_};
AddBuiltinOp(BuiltinOperator_LSTM, BuiltinOptions_LSTMOptions,
CreateLSTMOptions(builder_, ActivationFunctionType_TANH, 0.0,
0.0, LSTMKernelType_BASIC)
.Union(),
lstm_inputs, lstm_outputs);
if (prepend_noop) {
BuildInterpreter({GetShape(input_), GetShape(zero_input_),
GetShape(prev_output_), GetShape(weights_),
GetShape(biases_), GetShape(prev_cell_state_)});
} else {
BuildInterpreter({GetShape(input_), GetShape(prev_output_),
GetShape(weights_), GetShape(biases_),
GetShape(prev_cell_state_)});
}
// init feedback inputs to zero
std::vector<int16_t> initial_state(GetTensorSize(cell_state_out_), 0);
PopulateTensor(prev_cell_state_, initial_state);
std::vector<uint8_t> initial_prev_output(GetTensorSize(output_), 0);
PopulateTensor(prev_output_, initial_prev_output);
}
int inputSize() { return input_size_; }
int outputSize() { return output_size_; }
void setInput(const std::vector<uint8_t>& input) {
PopulateTensor(input_, input);
if (prepend_noop_) {
std::vector<uint8_t> zero(GetTensorSize(zero_input_), 128);
PopulateTensor(zero_input_, zero);
}
}
std::vector<uint8_t> getOutput() { return ExtractVector<uint8_t>(output_); }
private:
// Inputs
int input_;
int weights_;
int biases_;
int prev_cell_state_;
int prev_output_;
// Outputs
int cell_state_out_;
int output_;
int output_concat_temp_;
int output_activation_temp_;
int input_size_;
int output_size_;
bool prepend_noop_;
int zero_input_;
int sum_out_;
};
class QuantizedLstmTest : public ::testing::Test,
public testing::WithParamInterface<bool> {
protected:
void VerifyGoldens(const std::vector<std::vector<uint8_t>>& input,
const std::vector<std::vector<uint8_t>>& output,
QuantizedLSTMOpModel* lstm) {
const int numBatches = input.size();
ASSERT_GT(numBatches, 0);
const int inputSize = lstm->inputSize();
ASSERT_GT(inputSize, 0);
const int inputSequenceSize = input[0].size() / inputSize;
ASSERT_GT(inputSequenceSize, 0);
for (int i = 0; i < inputSequenceSize; ++i) {
std::vector<uint8_t> inputStep;
for (int b = 0; b < numBatches; ++b) {
const uint8_t* batchStart = input[b].data() + i * inputSize;
const uint8_t* batchEnd = batchStart + inputSize;
inputStep.insert(inputStep.end(), batchStart, batchEnd);
}
lstm->setInput(inputStep);
lstm->Invoke();
const int outputSize = lstm->outputSize();
std::vector<float> expected;
for (int b = 0; b < numBatches; ++b) {
const uint8_t* goldenBatchStart = output[b].data() + i * outputSize;
const uint8_t* goldenBatchEnd = goldenBatchStart + outputSize;
expected.insert(expected.end(), goldenBatchStart, goldenBatchEnd);
}
EXPECT_THAT(lstm->getOutput(), ElementsAreArray(expected));
}
}
};
// Inputs and weights in this test are random and the test only checks that the
// outputs are equal to outputs obtained from running TF Lite version of
// quantized LSTM on the same inputs.
TEST_P(QuantizedLstmTest, BasicQuantizedLstmTest) {
const int numBatches = 2;
const int inputSize = 2;
const int outputSize = 4;
float weightsScale = 0.00408021;
int weightsZeroPoint = 100;
bool prepend_dummy_node = GetParam();
QuantizedLSTMOpModel lstm(
numBatches, inputSize, weightsScale, weightsZeroPoint, outputSize,
// This data are copied from QuantizedLSTMTest.cpp in NNAPI source code
// I have to recompose the weight matrix before passing it to the model
// recurrentToInputWeights inputToInputWeights
{254, 206, 77, 168, 146, 250, 71, 20, 215, 6, 235, 171, 223, 7, 118, 225,
10, 218, 59, 130, 174, 26, 171, 108,
// recurrentToCellWeights inputToCellWeights
172, 60, 205, 65, 133, 34, 14, 0, 140, 168, 29, 49, 240, 223, 133, 56,
206, 109, 142, 64, 246, 216, 54, 183,
// recurrentToForgetWeights inputToForgetWeights
137, 240, 103, 52, 24, 50, 68, 51, 237, 112, 132, 179, 0, 220, 89, 23,
158, 110, 69, 4, 207, 253, 3, 169,
// recurrentToOutputWeights inputToOutputWeights
106, 214, 67, 23, 195, 187, 59, 158, 45, 3, 11, 99, 119, 132, 49, 205,
109, 10, 129, 218, 11, 98, 218, 48},
// inputGateBias
{-7876, 13488, -726, 32839,
// cellGateBias
39481, 48624, 48976, -21419,
// forgetGateBias
9206, -46884, -11693, -38724,
// outputGateBias
-58999, -17050, -41852, -40538},
prepend_dummy_node);
// clang-format on
// LSTM input is stored as numBatches x (sequenceLength x inputSize) vector.
std::vector<std::vector<uint8_t>> lstmInput;
// clang-format off
lstmInput = {{154, 166,
166, 179,
141, 141},
{100, 200,
50, 150,
111, 222}};
// clang-format on
// LSTM output is stored as numBatches x (sequenceLength x outputSize) vector.
std::vector<std::vector<uint8_t>> lstmGoldenOutput;
/*
This is the output used in NNAPI's QuantizedLSTMTest.cpp
I get slightly different values that are consistent running with or
without acceleration
lstmGoldenOutput = {{136, 150, 140, 115,
140, 151, 146, 112,
139, 153, 146, 114},
{135, 152, 138, 112,
136, 156, 142, 112,
141, 154, 146, 108}};
*/
// clang-format off
lstmGoldenOutput = {{131, 152, 136, 109,
138, 150, 145, 111,
139, 152, 146, 113},
{131, 153, 135, 107,
134, 154, 140, 111,
140, 154, 145, 108}};
// clang-format on
VerifyGoldens(lstmInput, lstmGoldenOutput, &lstm);
}
INSTANTIATE_TEST_SUITE_P(QuantizedLstmTest, QuantizedLstmTest,
testing::Values(false, true));
} // namespace
} // namespace tflite
<commit_msg>Fix quant_basic_lstm_test.cc: The previous output and state tensors need to be variable tensors.<commit_after>/* Copyright 2019 The TensorFlow Authors. All Rights Reserved.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
==============================================================================*/
#include <cstdint>
#include <initializer_list>
#include <memory>
#include <vector>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include "tensorflow/lite/interpreter.h"
#include "tensorflow/lite/kernels/kernel_util.h"
#include "tensorflow/lite/kernels/register.h"
#include "tensorflow/lite/kernels/test_util.h"
#include "tensorflow/lite/model.h"
namespace tflite {
namespace {
using ::testing::ElementsAreArray;
class QuantizedLSTMOpModel : public MultiOpModel {
public:
QuantizedLSTMOpModel(int numBatches, int inputSize, float weightsScale,
int32_t weightsZeroPoint, int outputSize,
std::initializer_list<uint8_t> weights,
std::initializer_list<int32_t> biases,
// If true the LTSM node will be preceded by a noop
// one (add to 0)
bool prepend_noop) {
std::vector<uint32_t> inputs;
input_size_ = inputSize;
output_size_ = outputSize;
prepend_noop_ = prepend_noop;
std::vector<int> input_shape{numBatches, inputSize};
std::vector<int> output_shape{numBatches, outputSize};
std::vector<int> weight_shape{4 * outputSize, outputSize + inputSize};
std::vector<int> state_shape{numBatches, outputSize};
std::vector<int> bias_shape{4 * outputSize};
std::vector<int> lstm_inputs;
const TensorData input_tensor_data{
TensorType_UINT8, input_shape, 0.0f, 0.0f, 1. / 128., 128};
if (prepend_noop) {
zero_input_ = AddInput(input_tensor_data);
} else {
zero_input_ = 0;
}
input_ = AddInput(input_tensor_data);
prev_output_ =
AddInput({TensorType_UINT8, output_shape, 0.0f, 0.0f, 1. / 128., 128},
/*is_variable=*/true);
// Biases and Weights have to be constant in order to allow NNAPI
// delegation
weights_ = AddConstInput<uint8_t>({TensorType_UINT8, weight_shape, 0.0f,
0.0f, weightsScale, weightsZeroPoint},
weights);
biases_ = AddConstInput<int32_t>(
{TensorType_INT32, bias_shape, 0.0f, 0.0f, weightsScale / 128, 0},
biases);
prev_cell_state_ =
AddInput({TensorType_INT16, state_shape, 0.0f, 0.0f, 1. / 2048., 0},
/*is_variable=*/true);
sum_out_ = AddOutput(input_tensor_data);
output_ =
AddOutput({TensorType_UINT8, output_shape, 0.0f, 0.0f, 1. / 128., 128});
cell_state_out_ =
AddOutput({TensorType_INT16, state_shape, 0.0f, 0.0f, 1. / 2048., 0});
output_concat_temp_ =
AddOutput({TensorType_UINT8, output_shape, 0.0f, 0.0f, 1. / 128., 128});
output_activation_temp_ =
AddOutput({TensorType_INT16, output_shape, 0.0f, 0.0f, 1. / 128., 128});
if (prepend_noop) {
AddBuiltinOp(
BuiltinOperator_ADD, BuiltinOptions_AddOptions,
CreateAddOptions(builder_, ActivationFunctionType_NONE).Union(),
{zero_input_, input_}, {sum_out_});
lstm_inputs.push_back(sum_out_);
} else {
lstm_inputs.push_back(input_);
}
lstm_inputs.push_back(prev_output_);
lstm_inputs.push_back(weights_);
lstm_inputs.push_back(biases_);
lstm_inputs.push_back(prev_cell_state_);
std::vector<int> lstm_outputs{output_, cell_state_out_, output_concat_temp_,
output_activation_temp_};
AddBuiltinOp(BuiltinOperator_LSTM, BuiltinOptions_LSTMOptions,
CreateLSTMOptions(builder_, ActivationFunctionType_TANH, 0.0,
0.0, LSTMKernelType_BASIC)
.Union(),
lstm_inputs, lstm_outputs);
if (prepend_noop) {
BuildInterpreter({GetShape(input_), GetShape(zero_input_),
GetShape(prev_output_), GetShape(weights_),
GetShape(biases_), GetShape(prev_cell_state_)});
} else {
BuildInterpreter({GetShape(input_), GetShape(prev_output_),
GetShape(weights_), GetShape(biases_),
GetShape(prev_cell_state_)});
}
// init feedback inputs to zero
std::vector<int16_t> initial_state(GetTensorSize(cell_state_out_), 0);
PopulateTensor(prev_cell_state_, initial_state);
std::vector<uint8_t> initial_prev_output(GetTensorSize(output_), 0);
PopulateTensor(prev_output_, initial_prev_output);
}
int inputSize() { return input_size_; }
int outputSize() { return output_size_; }
void setInput(const std::vector<uint8_t>& input) {
PopulateTensor(input_, input);
if (prepend_noop_) {
std::vector<uint8_t> zero(GetTensorSize(zero_input_), 128);
PopulateTensor(zero_input_, zero);
}
}
std::vector<uint8_t> getOutput() { return ExtractVector<uint8_t>(output_); }
private:
// Inputs
int input_;
int weights_;
int biases_;
int prev_cell_state_;
int prev_output_;
// Outputs
int cell_state_out_;
int output_;
int output_concat_temp_;
int output_activation_temp_;
int input_size_;
int output_size_;
bool prepend_noop_;
int zero_input_;
int sum_out_;
};
class QuantizedLstmTest : public ::testing::Test,
public testing::WithParamInterface<bool> {
protected:
void VerifyGoldens(const std::vector<std::vector<uint8_t>>& input,
const std::vector<std::vector<uint8_t>>& output,
QuantizedLSTMOpModel* lstm) {
const int numBatches = input.size();
ASSERT_GT(numBatches, 0);
const int inputSize = lstm->inputSize();
ASSERT_GT(inputSize, 0);
const int inputSequenceSize = input[0].size() / inputSize;
ASSERT_GT(inputSequenceSize, 0);
for (int i = 0; i < inputSequenceSize; ++i) {
std::vector<uint8_t> inputStep;
for (int b = 0; b < numBatches; ++b) {
const uint8_t* batchStart = input[b].data() + i * inputSize;
const uint8_t* batchEnd = batchStart + inputSize;
inputStep.insert(inputStep.end(), batchStart, batchEnd);
}
lstm->setInput(inputStep);
lstm->Invoke();
const int outputSize = lstm->outputSize();
std::vector<float> expected;
for (int b = 0; b < numBatches; ++b) {
const uint8_t* goldenBatchStart = output[b].data() + i * outputSize;
const uint8_t* goldenBatchEnd = goldenBatchStart + outputSize;
expected.insert(expected.end(), goldenBatchStart, goldenBatchEnd);
}
EXPECT_THAT(lstm->getOutput(), ElementsAreArray(expected));
}
}
};
// Inputs and weights in this test are random and the test only checks that the
// outputs are equal to outputs obtained from running TF Lite version of
// quantized LSTM on the same inputs.
TEST_P(QuantizedLstmTest, BasicQuantizedLstmTest) {
const int numBatches = 2;
const int inputSize = 2;
const int outputSize = 4;
float weightsScale = 0.00408021;
int weightsZeroPoint = 100;
bool prepend_dummy_node = GetParam();
QuantizedLSTMOpModel lstm(
numBatches, inputSize, weightsScale, weightsZeroPoint, outputSize,
// This data are copied from QuantizedLSTMTest.cpp in NNAPI source code
// I have to recompose the weight matrix before passing it to the model
// recurrentToInputWeights inputToInputWeights
{254, 206, 77, 168, 146, 250, 71, 20, 215, 6, 235, 171, 223, 7, 118, 225,
10, 218, 59, 130, 174, 26, 171, 108,
// recurrentToCellWeights inputToCellWeights
172, 60, 205, 65, 133, 34, 14, 0, 140, 168, 29, 49, 240, 223, 133, 56,
206, 109, 142, 64, 246, 216, 54, 183,
// recurrentToForgetWeights inputToForgetWeights
137, 240, 103, 52, 24, 50, 68, 51, 237, 112, 132, 179, 0, 220, 89, 23,
158, 110, 69, 4, 207, 253, 3, 169,
// recurrentToOutputWeights inputToOutputWeights
106, 214, 67, 23, 195, 187, 59, 158, 45, 3, 11, 99, 119, 132, 49, 205,
109, 10, 129, 218, 11, 98, 218, 48},
// inputGateBias
{-7876, 13488, -726, 32839,
// cellGateBias
39481, 48624, 48976, -21419,
// forgetGateBias
9206, -46884, -11693, -38724,
// outputGateBias
-58999, -17050, -41852, -40538},
prepend_dummy_node);
// clang-format on
// LSTM input is stored as numBatches x (sequenceLength x inputSize) vector.
std::vector<std::vector<uint8_t>> lstmInput;
// clang-format off
lstmInput = {{154, 166,
166, 179,
141, 141},
{100, 200,
50, 150,
111, 222}};
// clang-format on
// LSTM output is stored as numBatches x (sequenceLength x outputSize) vector.
std::vector<std::vector<uint8_t>> lstmGoldenOutput;
/*
This is the output used in NNAPI's QuantizedLSTMTest.cpp
I get slightly different values that are consistent running with or
without acceleration
lstmGoldenOutput = {{136, 150, 140, 115,
140, 151, 146, 112,
139, 153, 146, 114},
{135, 152, 138, 112,
136, 156, 142, 112,
141, 154, 146, 108}};
*/
// clang-format off
lstmGoldenOutput = {{131, 152, 136, 109,
138, 150, 145, 111,
139, 152, 146, 113},
{131, 153, 135, 107,
134, 154, 140, 111,
140, 154, 145, 108}};
// clang-format on
VerifyGoldens(lstmInput, lstmGoldenOutput, &lstm);
}
INSTANTIATE_TEST_SUITE_P(QuantizedLstmTest, QuantizedLstmTest,
testing::Values(false, true));
} // namespace
} // namespace tflite
<|endoftext|> |
<commit_before>// Copyright (c) 2011 The Chromium Authors. All rights reserved.
// Use of this source code is governed by a BSD-style license that can be
// found in the LICENSE file.
#include <vector>
#include "base/file_path.h"
#include "base/string_util.h"
#include "base/utf_string_conversions.h"
#include "chrome/browser/autofill/autofill_manager.h"
#include "chrome/browser/autofill/data_driven_test.h"
#include "chrome/browser/autofill/form_structure.h"
#include "chrome/browser/tab_contents/tab_contents.h"
#include "chrome/browser/ui/browser.h"
#include "chrome/test/in_process_browser_test.h"
#include "chrome/test/ui_test_utils.h"
#include "googleurl/src/gurl.h"
namespace {
const FilePath::CharType kTestName[] = FILE_PATH_LITERAL("heuristics");
const FilePath::CharType kFileNamePattern[] = FILE_PATH_LITERAL("*.html");
// Convert the |html| snippet to a data URI.
GURL HTMLToDataURI(const std::string& html) {
return GURL(std::string("data:text/html;charset=utf-8,") + html);
}
} // namespace
// A data-driven test for verifying AutoFill heuristics. Each input is an HTML
// file that contains one or more forms. The corresponding output file lists the
// heuristically detected type for eachfield.
class FormStructureBrowserTest : public InProcessBrowserTest,
public DataDrivenTest {
protected:
FormStructureBrowserTest();
virtual ~FormStructureBrowserTest();
// DataDrivenTest:
virtual void GenerateResults(const std::string& input,
std::string* output);
// Serializes the given |forms| into a string.
std::string FormStructuresToString(const std::vector<FormStructure*>& forms);
private:
DISALLOW_COPY_AND_ASSIGN(FormStructureBrowserTest);
};
FormStructureBrowserTest::FormStructureBrowserTest() {
}
FormStructureBrowserTest::~FormStructureBrowserTest() {
}
void FormStructureBrowserTest::GenerateResults(const std::string& input,
std::string* output) {
LOG(WARNING) << "Before NavigateToURL";
ASSERT_NO_FATAL_FAILURE(ui_test_utils::NavigateToURL(browser(),
HTMLToDataURI(input)));
LOG(WARNING) << "Before ClickOnView";
ASSERT_NO_FATAL_FAILURE(ui_test_utils::ClickOnView(browser(),
VIEW_ID_TAB_CONTAINER));
LOG(WARNING) << "Before IsViewFocused";
ASSERT_TRUE(ui_test_utils::IsViewFocused(browser(),
VIEW_ID_TAB_CONTAINER_FOCUS_VIEW));
LOG(WARNING) << "After IsViewFocused";
AutoFillManager* autofill_manager =
browser()->GetSelectedTabContents()->autofill_manager();
ASSERT_NE(static_cast<AutoFillManager*>(NULL), autofill_manager);
std::vector<FormStructure*> forms = autofill_manager->form_structures_.get();
*output = FormStructureBrowserTest::FormStructuresToString(forms);
}
std::string FormStructureBrowserTest::FormStructuresToString(
const std::vector<FormStructure*>& forms) {
std::string forms_string;
for (std::vector<FormStructure*>::const_iterator iter = forms.begin();
iter != forms.end();
++iter) {
for (std::vector<AutoFillField*>::const_iterator field_iter =
(*iter)->begin();
field_iter != (*iter)->end();
++field_iter) {
// The field list is NULL-terminated. Exit loop when at the end.
if (!*field_iter)
break;
forms_string += AutoFillType::FieldTypeToString((*field_iter)->type());
forms_string += "\n";
}
}
return forms_string;
}
IN_PROC_BROWSER_TEST_F(FormStructureBrowserTest, DataDrivenHeuristics) {
LOG(WARNING) << "Before BringBrowserWindowToFront";
ASSERT_TRUE(ui_test_utils::BringBrowserWindowToFront(browser()));
LOG(WARNING) << "After BringBrowserWindowToFront";
RunDataDrivenTest(GetInputDirectory(kTestName),
GetOutputDirectory(kTestName),
kFileNamePattern);
}
<commit_msg>Disable FormStructureBrowserTest.DataDrivenHeuristics<commit_after>// Copyright (c) 2011 The Chromium Authors. All rights reserved.
// Use of this source code is governed by a BSD-style license that can be
// found in the LICENSE file.
#include <vector>
#include "base/file_path.h"
#include "base/string_util.h"
#include "base/utf_string_conversions.h"
#include "chrome/browser/autofill/autofill_manager.h"
#include "chrome/browser/autofill/data_driven_test.h"
#include "chrome/browser/autofill/form_structure.h"
#include "chrome/browser/tab_contents/tab_contents.h"
#include "chrome/browser/ui/browser.h"
#include "chrome/test/in_process_browser_test.h"
#include "chrome/test/ui_test_utils.h"
#include "googleurl/src/gurl.h"
namespace {
const FilePath::CharType kTestName[] = FILE_PATH_LITERAL("heuristics");
const FilePath::CharType kFileNamePattern[] = FILE_PATH_LITERAL("*.html");
// Convert the |html| snippet to a data URI.
GURL HTMLToDataURI(const std::string& html) {
return GURL(std::string("data:text/html;charset=utf-8,") + html);
}
} // namespace
// A data-driven test for verifying AutoFill heuristics. Each input is an HTML
// file that contains one or more forms. The corresponding output file lists the
// heuristically detected type for eachfield.
class FormStructureBrowserTest : public InProcessBrowserTest,
public DataDrivenTest {
protected:
FormStructureBrowserTest();
virtual ~FormStructureBrowserTest();
// DataDrivenTest:
virtual void GenerateResults(const std::string& input,
std::string* output);
// Serializes the given |forms| into a string.
std::string FormStructuresToString(const std::vector<FormStructure*>& forms);
private:
DISALLOW_COPY_AND_ASSIGN(FormStructureBrowserTest);
};
FormStructureBrowserTest::FormStructureBrowserTest() {
}
FormStructureBrowserTest::~FormStructureBrowserTest() {
}
void FormStructureBrowserTest::GenerateResults(const std::string& input,
std::string* output) {
LOG(WARNING) << "Before NavigateToURL";
ASSERT_NO_FATAL_FAILURE(ui_test_utils::NavigateToURL(browser(),
HTMLToDataURI(input)));
LOG(WARNING) << "Before ClickOnView";
ASSERT_NO_FATAL_FAILURE(ui_test_utils::ClickOnView(browser(),
VIEW_ID_TAB_CONTAINER));
LOG(WARNING) << "Before IsViewFocused";
ASSERT_TRUE(ui_test_utils::IsViewFocused(browser(),
VIEW_ID_TAB_CONTAINER_FOCUS_VIEW));
LOG(WARNING) << "After IsViewFocused";
AutoFillManager* autofill_manager =
browser()->GetSelectedTabContents()->autofill_manager();
ASSERT_NE(static_cast<AutoFillManager*>(NULL), autofill_manager);
std::vector<FormStructure*> forms = autofill_manager->form_structures_.get();
*output = FormStructureBrowserTest::FormStructuresToString(forms);
}
std::string FormStructureBrowserTest::FormStructuresToString(
const std::vector<FormStructure*>& forms) {
std::string forms_string;
for (std::vector<FormStructure*>::const_iterator iter = forms.begin();
iter != forms.end();
++iter) {
for (std::vector<AutoFillField*>::const_iterator field_iter =
(*iter)->begin();
field_iter != (*iter)->end();
++field_iter) {
// The field list is NULL-terminated. Exit loop when at the end.
if (!*field_iter)
break;
forms_string += AutoFillType::FieldTypeToString((*field_iter)->type());
forms_string += "\n";
}
}
return forms_string;
}
IN_PROC_BROWSER_TEST_F(FormStructureBrowserTest,
DISABLED_DataDrivenHeuristics) {
LOG(WARNING) << "Before BringBrowserWindowToFront";
ASSERT_TRUE(ui_test_utils::BringBrowserWindowToFront(browser()));
LOG(WARNING) << "After BringBrowserWindowToFront";
RunDataDrivenTest(GetInputDirectory(kTestName),
GetOutputDirectory(kTestName),
kFileNamePattern);
}
<|endoftext|> |
<commit_before>#include <omp.h>
#include <stdio.h>
#include <opencv2/opencv.hpp>
#include <fstream>
#include <iostream>
#include <armadillo>
#include <iomanip>
#include <vector>
#include <hdf5.h>
#include "omp.h"
using namespace std;
using namespace arma;
// #include "aux-functions-def.hpp"
// #include "aux-functions-impl.hpp"
// #include "riemannian-metrics-def.hpp"
// #include "riemannian-metrics-impl.hpp"
#include "grassmann-metrics-def.hpp"
#include "grassmann-metrics-impl.hpp"
#include "kth-cross-validation-one-def.hpp"
#include "kth-cross-validation-one-impl.hpp"
//Home
//const std::string path = "/media/johanna/HD1T/codes/datasets_codes/KTH/";
//WANDA
const std::string path = "/home/johanna/codes/codes-git/study-paper/trunk/";
const std::string peopleList = "people_list.txt";
const std::string actionNames = "actionNames.txt";
///kth
// int ori_col = 160;
// int ori_row = 120;
int
main(int argc, char** argv)
{
if(argc < 3 )
{
cout << "usage: " << argv[0] << " scale_factor " << " shift_factor " << endl;
return -1;
}
int scale_factor = atoi( argv[1] );
int shift = atoi( argv[2] );
int total_scenes = 1; //Only for Scenario 1.
int dim = 14;
//int p = 12;//PQ NO SE> POR BOBA> FUE UN ERROR :(
field<string> all_people;
all_people.load(peopleList);
//Cross Validation
// kth_cv_omp kth_CV_omp_onesegment(path, actionNames, all_people, scale_factor, shift, total_scenes, dim);
// kth_CV_omp_onesegment.logEucl();
// kth_CV_omp_onesegment.SteinDiv();
// kth_CV_omp_onesegment.proj_grass(p);
vec vec_bc = zeros(dim);
vec vec_pm = zeros(dim);
for (int p=1; p<= dim; ++p)
{
kth_cv_omp kth_CV_omp_onesegment(path, actionNames, all_people, scale_factor, shift, total_scenes, dim);
vec_pm(p-1) = kth_CV_omp_onesegment.proj_grass(p);
vec_bc(p-1) = kth_CV_omp_onesegment.BC_grass(p);
}
vec_pm.t().print("Projection Metric");
vec_bc.t().print("Binet-Cauchy");
return 0;
}
<commit_msg>Re-run classification. One long segment. p=1:14<commit_after>#include <omp.h>
#include <stdio.h>
#include <opencv2/opencv.hpp>
#include <fstream>
#include <iostream>
#include <armadillo>
#include <iomanip>
#include <vector>
#include <hdf5.h>
#include "omp.h"
using namespace std;
using namespace arma;
// #include "aux-functions-def.hpp"
// #include "aux-functions-impl.hpp"
// #include "riemannian-metrics-def.hpp"
// #include "riemannian-metrics-impl.hpp"
#include "grassmann-metrics-def.hpp"
#include "grassmann-metrics-impl.hpp"
#include "kth-cross-validation-one-def.hpp"
#include "kth-cross-validation-one-impl.hpp"
//Home
//const std::string path = "/media/johanna/HD1T/codes/datasets_codes/KTH/";
//WANDA
const std::string path = "/home/johanna/codes/codes-git/study-paper/trunk/";
const std::string peopleList = "people_list.txt";
const std::string actionNames = "actionNames.txt";
///kth
// int ori_col = 160;
// int ori_row = 120;
int
main(int argc, char** argv)
{
if(argc < 3 )
{
cout << "usage: " << argv[0] << " scale_factor " << " shift_factor " << endl;
return -1;
}
int scale_factor = atoi( argv[1] );
int shift = atoi( argv[2] );
int total_scenes = 1; //Only for Scenario 1.
int dim = 14;
//int p = 12;//PQ NO SE> POR BOBA> FUE UN ERROR :(
field<string> all_people;
all_people.load(peopleList);
//Cross Validation
// kth_cv_omp kth_CV_omp_onesegment(path, actionNames, all_people, scale_factor, shift, total_scenes, dim);
// kth_CV_omp_onesegment.logEucl();
// kth_CV_omp_onesegment.SteinDiv();
// kth_CV_omp_onesegment.proj_grass(p);
vec vec_bc = zeros(dim);
vec vec_pm = zeros(dim);
for (int p=1; p<= dim; ++p)
{
cout << "p= " << p << endl;
kth_cv_omp kth_CV_omp_onesegment(path, actionNames, all_people, scale_factor, shift, total_scenes, dim);
vec_pm(p-1) = kth_CV_omp_onesegment.proj_grass(p);
vec_bc(p-1) = kth_CV_omp_onesegment.BC_grass(p);
}
vec_pm.t().print("Projection Metric");
vec_bc.t().print("Binet-Cauchy");
return 0;
}
<|endoftext|> |
<commit_before>#include "geometria/CurvaBSpline.h"
#include <iostream>
CurvaBSpline::CurvaBSpline() :
ObjetoGeometrico() {
this->pontosParametricosRedefinidos = false;
}
CurvaBSpline::CurvaBSpline(const CurvaBSpline& curva) :
ObjetoGeometrico(curva) {
for (int i = 0; i < curva.pontos.size(); i++)
this->pontos.insert(i, curva.pontos.at(i));
this->pontosParametricos = curva.pontosParametricos;
this->pontosParametricosRedefinidos = curva.pontosParametricosRedefinidos;
}
CurvaBSpline::CurvaBSpline(const String& nome, const QList<Ponto>& pontos,
const QColor& cor) :
ObjetoGeometrico(nome, Tipo::CURVA_BSPLINE, cor) {
for (int i = 0; i < pontos.size(); i++)
this->pontos.insert(i, pontos.at(i));
this->pontosParametricos = this->calcularPontosParametricos();
this->pontosParametricosRedefinidos = false;
}
CurvaBSpline::~CurvaBSpline() {}
CurvaBSpline& CurvaBSpline::operator=(const CurvaBSpline& curva) {
this->ObjetoGeometrico::operator =(curva);
this->pontos.clear();
for (int i = 0; i < curva.pontos.size(); i++)
this->pontos.insert(i, curva.pontos.at(i));
this->pontosParametricos = curva.pontosParametricos;
this->pontosParametricosRedefinidos = curva.pontosParametricosRedefinidos;
return *this;
}
ObjetoGeometrico* CurvaBSpline::clonar() const {
return new CurvaBSpline(*this);
}
QList<Ponto> CurvaBSpline::getPontos() const {
if (!this->pontosParametricosRedefinidos)
return this->calcularPontosParametricos();
std::cout << this->pontosParametricos.size() << std::endl;
return this->pontosParametricos;
}
QList<Ponto*> CurvaBSpline::getPontosObjeto() {
QList<Ponto*> lista;
for (int i = 0; i < this->pontos.size(); i++)
lista.insert(i, (Ponto*) &this->pontos.at(i));
return lista;
}
const String CurvaBSpline::toString() const {
String retorno = "[" + this->pontos.at(0).toString();
for (int i = 1; i < this->pontos.size(); i++) {
retorno += ", " + this->pontos.at(i).toString();
}
retorno += "]";
return retorno;
}
void CurvaBSpline::setPontosParametricos(const QList<Ponto>& pontos) {
this->pontosParametricos = pontos;
this->pontosParametricosRedefinidos = true;
}
QList<Ponto> CurvaBSpline::calcularPontosParametricos(const double t) const {
QList<Ponto> pontos;
int tam = this->pontos.size();
// Calcular os pontos do segmento Qm (m-3 ... m)
for (int m = 3; m < tam; m++) {
Ponto p[4] = { this->pontos.at(m-3), this->pontos.at(m-2),
this->pontos.at(m-1), this->pontos.at(m) };
QList<Ponto> novosPontos =
this->calcularPontosParametricosIntermediario(p, t);
for (int i = 0; i < novosPontos.size(); i++)
pontos.insert(pontos.size(), novosPontos.at(i));
}
// *** NÃO ENTENDI O PQ DISSO ***
// //pega os últimos 4 pontos para calcular a parte final da reta
//
// Ponto p[4] = { this->pontos.at(tam - 4), this->pontos.at(tam - 3),
// this->pontos.at(tam - 2), this->pontos.at(tam - 1) };
// QList<Ponto> novosPontos = this->calcularPontosParametricosIntermediario(p,
// t, 3);
// for (int j = 0; j < novosPontos.size(); j++) {
// pontos.insert(pontos.size(), novosPontos.at(j));
// }
/**
* Mbs
1/6 x
-1 3 -3 1
3 -6 3 0
-3 0 3 0
1 3 1 0
Mbs-1
0 2/3 -1 1
0 -1/3 0 1
0 2/3 1 1
6 11/3 2 1
a = 2/3*p[1] - p[2] + p[3]
b = -1/3*p[1] + p[3]
c = 2/3*p[1] + p[2] + p[3]
d = 6*p[0] + 11/3*p[1] + 2*p[2] + p[3]
*/
return pontos;
}
QList<Ponto> CurvaBSpline::calcularPontosParametricosIntermediario(Ponto *p, const double t) const {
// Cálculo dos coeficientes (a, b, c, d)
double p0[3] = { p[0].getX(), p[0].getY(), p[0].getZ() };
double p1[3] = { p[1].getX(), p[1].getY(), p[1].getZ() };
double p2[3] = { p[2].getX(), p[2].getY(), p[2].getZ() };
double p3[3] = { p[3].getX(), p[3].getY(), p[3].getZ() };
double cfA[3] = { 0, 0, 0 };
double cfB[3] = { 0, 0, 0 };
double cfC[3] = { 0, 0, 0 };
double cfD[3] = { 0, 0, 0 };
for(int i = 0; i < 4; i++) {
cfA[i] = (2/3)*p1[i] - p2[i] + p3[i];
cfB[i] = -(1/3)*p1[i] + p3[i];
cfC[i] = (2/3)*p1[i] + p2[i] + p3[i];
cfD[i] = 6*p0[i] + (11/3)*p1[i] + 2*p2[i] + p3[i];
}
// Cálculo das diferenças iniciais (f0, df0, d²f0, d³f0)
double dt = t;
double dt2 = pow(t, 2);
double dt3 = pow(t, 3);
double dInicialX[4] = { cfD[0],
dt3*cfA[0] + dt2*cfB[0] + cfC[0],
6*dt3*cfA[0] + 2*dt2*cfB[0],
6*dt3*cfA[0] };
double dInicialY[4] = { cfD[1],
dt3*cfA[1] + dt2*cfB[1] + cfC[1],
6*dt3*cfA[1] + 2*dt2*cfB[1],
6*dt3*cfA[1] };
double dInicialZ[4] = { cfD[2],
dt3*cfA[2] + dt2*cfB[2] + cfC[2],
6*dt3*cfA[2] + 2*dt2*cfB[2],
6*dt3*cfA[2] };
QList<Ponto> pontos;
pontos.insert(0, Ponto("", 0, 0, 0));
double n = 1/t;
for(int i = 0; i < n; i++) {
}
while (x[0] < p[n].getX()) {
x[0] += deltaX;
deltaX += delta2X;
delta2X += delta3X;
y[0] += deltaY;
deltaY += delta2Y;
delta2Y += delta3Y;
z[0] += deltaZ;
deltaZ += delta2Z;
delta2Z += delta3Z;
pontos.insert(pontos.size(), Ponto("", x[0], y[0], z[0]));
}
return this->pontos;
}
<commit_msg>Algoritmo da curva B-Spline refatorado (não está funcionando).<commit_after>#include "geometria/CurvaBSpline.h"
#include <iostream>
CurvaBSpline::CurvaBSpline() :
ObjetoGeometrico() {
this->pontosParametricosRedefinidos = false;
}
CurvaBSpline::CurvaBSpline(const CurvaBSpline& curva) :
ObjetoGeometrico(curva) {
for (int i = 0; i < curva.pontos.size(); i++)
this->pontos.insert(i, curva.pontos.at(i));
this->pontosParametricos = curva.pontosParametricos;
this->pontosParametricosRedefinidos = curva.pontosParametricosRedefinidos;
}
CurvaBSpline::CurvaBSpline(const String& nome, const QList<Ponto>& pontos,
const QColor& cor) :
ObjetoGeometrico(nome, Tipo::CURVA_BSPLINE, cor) {
for (int i = 0; i < pontos.size(); i++)
this->pontos.insert(i, pontos.at(i));
this->pontosParametricos = this->calcularPontosParametricos();
this->pontosParametricosRedefinidos = false;
}
CurvaBSpline::~CurvaBSpline() {}
CurvaBSpline& CurvaBSpline::operator=(const CurvaBSpline& curva) {
this->ObjetoGeometrico::operator =(curva);
this->pontos.clear();
for (int i = 0; i < curva.pontos.size(); i++)
this->pontos.insert(i, curva.pontos.at(i));
this->pontosParametricos = curva.pontosParametricos;
this->pontosParametricosRedefinidos = curva.pontosParametricosRedefinidos;
return *this;
}
ObjetoGeometrico* CurvaBSpline::clonar() const {
return new CurvaBSpline(*this);
}
QList<Ponto> CurvaBSpline::getPontos() const {
if (!this->pontosParametricosRedefinidos)
return this->calcularPontosParametricos();
std::cout << this->pontosParametricos.size() << std::endl;
return this->pontosParametricos;
}
QList<Ponto*> CurvaBSpline::getPontosObjeto() {
QList<Ponto*> lista;
for (int i = 0; i < this->pontos.size(); i++)
lista.insert(i, (Ponto*) &this->pontos.at(i));
return lista;
}
const String CurvaBSpline::toString() const {
String retorno = "[" + this->pontos.at(0).toString();
for (int i = 1; i < this->pontos.size(); i++) {
retorno += ", " + this->pontos.at(i).toString();
}
retorno += "]";
return retorno;
}
void CurvaBSpline::setPontosParametricos(const QList<Ponto>& pontos) {
this->pontosParametricos = pontos;
this->pontosParametricosRedefinidos = true;
}
QList<Ponto> CurvaBSpline::calcularPontosParametricos(const double t) const {
QList<Ponto> pontosParam;
int tam = this->pontos.size();
// Calcular os pontos do segmento Qm (m-3 ... m)
for (int m = 3; m < tam; m++) {
Ponto p[4] = { this->pontos.at(m-3), this->pontos.at(m-2),
this->pontos.at(m-1), this->pontos.at(m) };
QList<Ponto> novosPontos =
this->calcularPontosParametricosIntermediario(p, t);
for (Ponto p : novosPontos)
pontosParam.insert(pontosParam.size(), p);
}
return pontosParam;
}
QList<Ponto> CurvaBSpline::calcularPontosParametricosIntermediario(Ponto *p, const double t) const {
// Cálculo dos coeficientes (a, b, c, d)
double p0[3] = { p[0].getX(), p[0].getY(), p[0].getZ() };
double p1[3] = { p[1].getX(), p[1].getY(), p[1].getZ() };
double p2[3] = { p[2].getX(), p[2].getY(), p[2].getZ() };
double p3[3] = { p[3].getX(), p[3].getY(), p[3].getZ() };
double cfA[3] = { 0, 0, 0 };
double cfB[3] = { 0, 0, 0 };
double cfC[3] = { 0, 0, 0 };
double cfD[3] = { 0, 0, 0 };
for(int i = 0; i < 3; i++) {
cfA[i] = (2/3)*p1[i] - p2[i] + p3[i];
cfB[i] = -(1/3)*p1[i] + p3[i];
cfC[i] = (2/3)*p1[i] + p2[i] + p3[i];
cfD[i] = 6*p0[i] + (11/3)*p1[i] + 2*p2[i] + p3[i];
}
// Cálculo das diferenças iniciais (f0, df0, d²f0, d³f0)
double dt = t;
double dt2 = pow(t, 2);
double dt3 = pow(t, 3);
double dInicialX[4] = { cfD[0],
dt3*cfA[0] + dt2*cfB[0] + dt*cfC[0],
6*dt3*cfA[0] + 2*dt2*cfB[0],
6*dt3*cfA[0] };
double dInicialY[4] = { cfD[1],
dt3*cfA[1] + dt2*cfB[1] + dt*cfC[1],
6*dt3*cfA[1] + 2*dt2*cfB[1],
6*dt3*cfA[1] };
double dInicialZ[4] = { cfD[2],
dt3*cfA[2] + dt2*cfB[2] + dt*cfC[2],
6*dt3*cfA[2] + 2*dt2*cfB[2],
6*dt3*cfA[2] };
// Cálculo dos pontos paramétricos
QList<Ponto> pontosParam;
pontosParam.insert(0, Ponto("", dInicialX[0], dInicialY[0], dInicialZ[0]));
double n = 1/t;
for(int i = 1; i < n; i++) {
dInicialX[0] += dInicialX[1];
dInicialY[0] += dInicialY[1];
dInicialZ[0] += dInicialZ[1];
dInicialX[1] += dInicialX[2];
dInicialY[1] += dInicialY[2];
dInicialZ[1] += dInicialZ[2];
dInicialX[2] += dInicialX[3];
dInicialY[2] += dInicialY[3];
dInicialZ[2] += dInicialZ[3];
pontosParam.insert(i, Ponto("", dInicialX[0], dInicialY[0], dInicialZ[0]));
}
return pontosParam;
}
<|endoftext|> |
<commit_before>/*
This file is part of cpp-ethereum.
cpp-ethereum is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
cpp-ethereum is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with cpp-ethereum. If not, see <http://www.gnu.org/licenses/>.
*/
/** @file gasPricer.cpp
* @author Christoph Jentzsch <cj@ethdev.com>
* @date 2015
*/
#include <libtestutils/BlockChainLoader.h>
#include <libethcore/Ethash.h>
#include <libethereum/CanonBlockChain.h>
#include <libethereum/GasPricer.h>
#include <libethereum/BasicGasPricer.h>
#include "../TestHelper.h"
using namespace std;
using namespace dev;
using namespace dev::eth;
namespace dev { namespace test {
void executeGasPricerTest(const string name, double _etherPrice, double _blockFee, const string bcTestPath, TransactionPriority _txPrio, u256 _expectedAsk, u256 _expectedBid)
{
cnote << name;
BasicGasPricer gp(u256(double(ether / 1000) / _etherPrice), u256(_blockFee * 1000));
Json::Value vJson = test::loadJsonFromFile(test::getTestPath() + bcTestPath);
test::BlockChainLoader bcLoader(vJson[name]);
BlockChain const& bc = bcLoader.bc();
gp.update(bc);
BOOST_CHECK_EQUAL(gp.ask(State()), _expectedAsk);
BOOST_CHECK_EQUAL(gp.bid(_txPrio), _expectedBid);
}
} }
BOOST_AUTO_TEST_SUITE(GasPricer)
BOOST_AUTO_TEST_CASE(trivialGasPricer)
{
cnote << "trivialGasPricer";
std::shared_ptr<dev::eth::GasPricer> gp(new TrivialGasPricer);
BOOST_CHECK_EQUAL(gp->ask(State()), 10 * szabo);
BOOST_CHECK_EQUAL(gp->bid(), 10 * szabo);
gp->update(CanonBlockChain<Ethash>(TransientDirectory().path(), WithExisting::Kill));
BOOST_CHECK_EQUAL(gp->ask(State()), 10 * szabo);
BOOST_CHECK_EQUAL(gp->bid(), 10 * szabo);
}
BOOST_AUTO_TEST_CASE(basicGasPricerNoUpdate)
{
cnote << "basicGasPricer";
BasicGasPricer gp(u256(double(ether / 1000) / 30.679), u256(15.0 * 1000));
BOOST_CHECK_EQUAL(gp.ask(State()), 155632494086);
BOOST_CHECK_EQUAL(gp.bid(), 155632494086);
gp.setRefPrice(u256(0));
BOOST_CHECK_EQUAL(gp.ask(State()), 0);
BOOST_CHECK_EQUAL(gp.bid(), 0);
gp.setRefPrice(u256(1));
gp.setRefBlockFees(u256(0));
BOOST_CHECK_EQUAL(gp.ask(State()), 0);
BOOST_CHECK_EQUAL(gp.bid(), 0);
gp.setRefPrice(u256("0x100000000000000000000000000000000"));
BOOST_CHECK_THROW(gp.setRefBlockFees(u256("0x100000000000000000000000000000000")), Overflow);
BOOST_CHECK_EQUAL(gp.ask(State()), 0);
BOOST_CHECK_EQUAL(gp.bid(), 0);
gp.setRefPrice(1);
gp.setRefBlockFees(u256("0x100000000000000000000000000000000"));
BOOST_CHECK_THROW(gp.setRefPrice(u256("0x100000000000000000000000000000000")), Overflow);
BOOST_CHECK_EQUAL(gp.ask(State()), u256("108315264019305646138446560671076"));
BOOST_CHECK_EQUAL(gp.bid(), u256("108315264019305646138446560671076"));
}
BOOST_AUTO_TEST_CASE(basicGasPricer_RPC_API_Test)
{
dev::test::executeGasPricerTest("RPC_API_Test", 30.679, 15.0, "/BlockchainTests/bcRPC_API_Test.json", TransactionPriority::Medium, 155632494086, 1);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_bcValidBlockTest)
{
dev::test::executeGasPricerTest("SimpleTx", 30.679, 15.0, "/BlockchainTests/bcValidBlockTest.json", TransactionPriority::Medium, 155632494086, 10);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_bcUncleTest)
{
dev::test::executeGasPricerTest("twoUncle", 30.679, 15.0, "/BlockchainTests/bcUncleTest.json", TransactionPriority::Medium, 155632494086, 1);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_bcUncleHeaderValiditiy)
{
dev::test::executeGasPricerTest("correct", 30.679, 15.0, "/BlockchainTests/bcUncleHeaderValiditiy.json", TransactionPriority::Medium, 155632494086, 1);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_notxs)
{
dev::test::executeGasPricerTest("notxs", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Medium, 155632494086, 155632494086);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_LowestPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Lowest, 15731282021, 10000000000000);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_LowPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Low, 15731282021, 15734152261884);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_MediumPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Medium, 15731282021, 20000000000000);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_HighPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::High, 15731282021, 24265847738115);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_HighestPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Highest, 15731282021, 30000000000000);
}
BOOST_AUTO_TEST_SUITE_END()
<commit_msg>add documentation<commit_after>/*
This file is part of cpp-ethereum.
cpp-ethereum is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
cpp-ethereum is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with cpp-ethereum. If not, see <http://www.gnu.org/licenses/>.
*/
/** @file gasPricer.cpp
* @author Christoph Jentzsch <cj@ethdev.com>
* @date 2015
* Gas pricer tests
*/
#include <libtestutils/BlockChainLoader.h>
#include <libethcore/Ethash.h>
#include <libethereum/CanonBlockChain.h>
#include <libethereum/GasPricer.h>
#include <libethereum/BasicGasPricer.h>
#include "../TestHelper.h"
using namespace std;
using namespace dev;
using namespace dev::eth;
namespace dev { namespace test {
void executeGasPricerTest(const string name, double _etherPrice, double _blockFee, const string bcTestPath, TransactionPriority _txPrio, u256 _expectedAsk, u256 _expectedBid)
{
cnote << name;
BasicGasPricer gp(u256(double(ether / 1000) / _etherPrice), u256(_blockFee * 1000));
Json::Value vJson = test::loadJsonFromFile(test::getTestPath() + bcTestPath);
test::BlockChainLoader bcLoader(vJson[name]);
BlockChain const& bc = bcLoader.bc();
gp.update(bc);
BOOST_CHECK_EQUAL(gp.ask(State()), _expectedAsk);
BOOST_CHECK_EQUAL(gp.bid(_txPrio), _expectedBid);
}
} }
BOOST_AUTO_TEST_SUITE(GasPricer)
BOOST_AUTO_TEST_CASE(trivialGasPricer)
{
cnote << "trivialGasPricer";
std::shared_ptr<dev::eth::GasPricer> gp(new TrivialGasPricer);
BOOST_CHECK_EQUAL(gp->ask(State()), 10 * szabo);
BOOST_CHECK_EQUAL(gp->bid(), 10 * szabo);
gp->update(CanonBlockChain<Ethash>(TransientDirectory().path(), WithExisting::Kill));
BOOST_CHECK_EQUAL(gp->ask(State()), 10 * szabo);
BOOST_CHECK_EQUAL(gp->bid(), 10 * szabo);
}
BOOST_AUTO_TEST_CASE(basicGasPricerNoUpdate)
{
cnote << "basicGasPricer";
BasicGasPricer gp(u256(double(ether / 1000) / 30.679), u256(15.0 * 1000));
BOOST_CHECK_EQUAL(gp.ask(State()), 155632494086);
BOOST_CHECK_EQUAL(gp.bid(), 155632494086);
gp.setRefPrice(u256(0));
BOOST_CHECK_EQUAL(gp.ask(State()), 0);
BOOST_CHECK_EQUAL(gp.bid(), 0);
gp.setRefPrice(u256(1));
gp.setRefBlockFees(u256(0));
BOOST_CHECK_EQUAL(gp.ask(State()), 0);
BOOST_CHECK_EQUAL(gp.bid(), 0);
gp.setRefPrice(u256("0x100000000000000000000000000000000"));
BOOST_CHECK_THROW(gp.setRefBlockFees(u256("0x100000000000000000000000000000000")), Overflow);
BOOST_CHECK_EQUAL(gp.ask(State()), 0);
BOOST_CHECK_EQUAL(gp.bid(), 0);
gp.setRefPrice(1);
gp.setRefBlockFees(u256("0x100000000000000000000000000000000"));
BOOST_CHECK_THROW(gp.setRefPrice(u256("0x100000000000000000000000000000000")), Overflow);
BOOST_CHECK_EQUAL(gp.ask(State()), u256("108315264019305646138446560671076"));
BOOST_CHECK_EQUAL(gp.bid(), u256("108315264019305646138446560671076"));
}
BOOST_AUTO_TEST_CASE(basicGasPricer_RPC_API_Test)
{
dev::test::executeGasPricerTest("RPC_API_Test", 30.679, 15.0, "/BlockchainTests/bcRPC_API_Test.json", TransactionPriority::Medium, 155632494086, 1);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_bcValidBlockTest)
{
dev::test::executeGasPricerTest("SimpleTx", 30.679, 15.0, "/BlockchainTests/bcValidBlockTest.json", TransactionPriority::Medium, 155632494086, 10);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_bcUncleTest)
{
dev::test::executeGasPricerTest("twoUncle", 30.679, 15.0, "/BlockchainTests/bcUncleTest.json", TransactionPriority::Medium, 155632494086, 1);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_bcUncleHeaderValiditiy)
{
dev::test::executeGasPricerTest("correct", 30.679, 15.0, "/BlockchainTests/bcUncleHeaderValiditiy.json", TransactionPriority::Medium, 155632494086, 1);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_notxs)
{
dev::test::executeGasPricerTest("notxs", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Medium, 155632494086, 155632494086);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_LowestPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Lowest, 15731282021, 10000000000000);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_LowPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Low, 15731282021, 15734152261884);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_MediumPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Medium, 15731282021, 20000000000000);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_HighPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::High, 15731282021, 24265847738115);
}
BOOST_AUTO_TEST_CASE(basicGasPricer_highGasUsage_HighestPrio)
{
dev::test::executeGasPricerTest("highGasUsage", 30.679, 15.0, "/BlockchainTests/bcGasPricerTest.json", TransactionPriority::Highest, 15731282021, 30000000000000);
}
BOOST_AUTO_TEST_SUITE_END()
<|endoftext|> |
<commit_before>/*
Copyright (c) 2019, Michael Fisher <mfisher@kushview.net>
Permission to use, copy, modify, and/or distribute this software for any
purpose with or without fee is hereby granted, provided that the above
copyright notice and this permission notice appear in all copies.
THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
*/
/** @defgroup resize_port Resize Port
Resizing plugin ports
*/
#pragma once
#include <lvtk/ext/extension.hpp>
#include <lvtk/port_resizer.hpp>
namespace lvtk {
/** Adds a Logger `log` to your instance
@ingroup resize_port
@headerfile lvtk/ext/resize_port.hpp
*/
template<class I>
struct ResizePort : NullExtension
{
/** @private */
ResizePort (const FeatureList& features) {
for (const auto& f : features) {
if (resizer.set_feature (f))
break;
}
}
/** Call this to request the host resize a port */
inline ResizePortStatus resize_port (uint32_t index, uint32_t size) {
return resizer.resize (index, size);
}
private:
PortResizer resizer;
};
}
<commit_msg>Update docs<commit_after>/*
Copyright (c) 2019, Michael Fisher <mfisher@kushview.net>
Permission to use, copy, modify, and/or distribute this software for any
purpose with or without fee is hereby granted, provided that the above
copyright notice and this permission notice appear in all copies.
THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
*/
/** @defgroup resize_port Resize Port
Resizing plugin ports
*/
#pragma once
#include <lvtk/ext/extension.hpp>
#include <lvtk/port_resizer.hpp>
namespace lvtk {
/** Adds Port Resize support
@ingroup resize_port
@headerfile lvtk/ext/resize_port.hpp
*/
template<class I>
struct ResizePort : NullExtension
{
/** @private */
ResizePort (const FeatureList& features) {
for (const auto& f : features) {
if (resizer.set_feature (f))
break;
}
}
/** Call this to request the host resize a port */
inline ResizePortStatus resize_port (uint32_t index, uint32_t size) {
return resizer.resize (index, size);
}
private:
PortResizer resizer;
};
}
<|endoftext|> |
<commit_before>#include "cpuMLFQ.h"
void MLFQ::start()
{
init();
do {
/*thread docpu(&MLFQ::do_CPU, this);
thread doio(&MLFQ::do_IO, this);
doio.join();
docpu.join();*/
if (!IO->empty())
do_IO();
do_CPU();
} while (!queue1->empty() || !queue2->empty() || !fcfs->empty() || !IO->empty());
}
void MLFQ::init()
{
shared_ptr<qnode> P1 = make_shared<qnode>(); //{ 18, 41, 16, 52, 19, 31, 14, 33, 17, 43, 19, 66, 14, 39, 17 }
shared_ptr<qnode> P2 = make_shared<qnode>(); //{ 8, 32, 7, 42, 6, 27, 17, 41, 7, 33, 11, 43, 12, 32, 14 }
shared_ptr<qnode> P3 = make_shared<qnode>(); //{ 6, 51, 5, 53, 6, 46, 9, 32, 11, 52, 4, 61, 8 }
shared_ptr<qnode> P4 = make_shared<qnode>(); //{ 25, 35, 19, 41, 21, 45, 18, 51, 12, 61, 24, 54, 23, 61, 21 }
shared_ptr<qnode> P5 = make_shared<qnode>(); //{ 15, 61, 16, 52, 15, 71, 13, 41, 15, 62, 14, 31, 14, 41, 13, 32, 15 }
shared_ptr<qnode> P6 = make_shared<qnode>(); //{ 6, 25, 5, 31, 6, 32, 5, 41, 4, 81, 8, 39, 11, 42, 5 }
shared_ptr<qnode> P7 = make_shared<qnode>(); //{ 16, 38, 17, 41, 15, 29, 14, 26, 9, 32, 5, 34, 8, 26, 6, 39, 5 }
shared_ptr<qnode> P8 = make_shared<qnode>(); //{5, 52, 4, 42, 6, 31, 7, 21, 4, 43, 5, 31, 7, 32, 6, 32, 7, 41, 4}
shared_ptr<qnode> P9 = make_shared<qnode>(); //{ 11, 37, 12, 41, 6, 41, 4, 48, 6, 41, 5, 29, 4, 26, 5, 31, 3 }
P1->CPU_burst = { 17, 14, 19, 17, 14, 19, 16, 18 };
P1->IO_time = { 39, 66, 43, 33, 31, 52, 41 };
P2->CPU_burst = { 14, 12, 11, 7, 17, 6, 7, 8 };
P2->IO_time = { 32, 43, 41, 27, 42, 32 };
P3->CPU_burst = { 8, 4, 11, 9, 6, 5, 6 };
P3->IO_time = { 61,52,32,46,53,51 };
P4->CPU_burst = { 21,23,24,12,18,21,19,25 };
P4->IO_time = { 61, 54, 61, 51, 45, 41, 35 };
P5->CPU_burst = { 15,13,14,14,15,13,15,16,15 };
P5->IO_time = { 32, 41, 31, 62, 41, 71, 52, 61 };
P6->CPU_burst = { 5, 11, 8, 4, 5, 6, 5, 6 };
P6->IO_time = { 42, 39, 81, 41, 32, 31, 25 };
P7->CPU_burst = { 5, 6, 8, 5, 9, 14, 15, 17, 16 };
P7->IO_time = { 39, 26, 34, 32, 26, 29, 41, 38 };
P8->CPU_burst = { 4, 7, 6, 7, 5, 4, 7, 6, 4, 5 };
P8->IO_time = { 41, 32, 32, 31, 43, 21, 31, 42, 52 };
P9->CPU_burst = { 3, 5, 4, 5, 6, 4, 6, 12, 11 };
P9->IO_time = { 31, 26, 29, 41, 48, 41, 41, 37 };
P1->name = "P1";
P2->name = "P2";
P3->name = "P3";
P4->name = "P4";
P5->name = "P5";
P6->name = "P6";
P7->name = "P7";
P8->name = "P8";
P9->name = "P9";
queue1->Enqueue(P1);
queue1->Enqueue(P2);
queue1->Enqueue(P3);
queue1->Enqueue(P4);
queue1->Enqueue(P5);
queue1->Enqueue(P6);
queue1->Enqueue(P7);
queue1->Enqueue(P8);
queue1->Enqueue(P9);
}
void MLFQ::print()
{
cout << ".................................................." << endl << endl;
cout << "Ready Queue:\tProcess\t\tBurst\t\tQueue" << endl;
shared_ptr<qnode> newNode = queue1->get_front();
while (newNode != 0)
{
cout << "\t\t" << newNode->name << "\t\t" << newNode->CPU_burst.back()<< "\t\t" <<newNode->qu << endl;
newNode = newNode->next;
}
newNode = queue2->get_front();
while (newNode != 0)
{
cout << "\t\t" << newNode->name << "\t\t" << newNode->CPU_burst.back() << "\t\t" << newNode->qu << endl;
newNode = newNode->next;
}
newNode = fcfs->get_front();
while (newNode != 0)
{
cout << "\t\t" << newNode->name << "\t\t" << newNode->CPU_burst.back() << "\t\t" << newNode->qu << endl;
newNode = newNode->next;
}
cout << ".................................................." << endl<<endl;
cout << "Now in IO:\tProcess\t\tRemaining I/O time\n" << IO << endl;
}
void MLFQ::CPU_time_quantom_7()
{
shared_ptr<qnode> node = queue1->get_front();
if (node->time_on == 0)
{
cout << "Current time: " << counter << "\nCurrently Running: " << node->name << endl;
print();
}
node->CPU_burst.back()--;
node->time_on++;
if (node->CPU_burst.back() == 0)
{
node->CPU_burst.pop_back();
node->time_on = 0;
node->qu = "";
queue1->Dequeue();
IO->Enqueue(node);
}
else if (node->time_on == 7)
{
node->priority++;
node->qu = "Q2";
queue1->Dequeue();
queue2->Enqueue(node);
node->time_on = 0;
}
}
void MLFQ::CPU_fcfs()
{
shared_ptr<qnode> node = fcfs->get_front();
if (node->time_on == 0)
{
cout << "Current time: " << counter << "\nCurrently Running: " << node->name << endl;
print();
}
node->CPU_burst.back()--;
node->time_on++;
if (node->CPU_burst.back() == 0)
{
node->CPU_burst.pop_back();
node->time_on = 0;
node->qu = "";
fcfs->Dequeue();
IO->Enqueue(node);
}
}
void MLFQ::do_IO()
{
shared_ptr<qnode> nodeParent = 0;
shared_ptr<qnode> node = IO->get_front();
while (node != 0)
{
node->IO_time.back()--;
if (node->IO_time.back() == 0)
{
IO->remove_node(node);
switch (node->priority)
{
case 1:
node->qu = "Q1";
queue1->Enqueue(node);
break;
case 2:
node->qu = "Q2";
queue2->Enqueue(node);
break;
case 3:
node->qu = "FCFS";
fcfs->Enqueue(node);
break;
default:
cout << "error\n";
break;
}
node->IO_time.pop_back();
}
node = node->next;
}
}
void MLFQ::do_CPU()
{
if (!queue1->empty())
{
CPU_time_quantom_7();
}
else if (!queue2->empty())
{
CPU_time_quantom_14();
}
else if (!fcfs->empty())
{
CPU_fcfs();
}
else
cout << "CPU Idle";
counter++;
}
void MLFQ::CPU_time_quantom_14()
{
shared_ptr<qnode> node = queue2->get_front();
node->CPU_burst.back()--;
node->time_on++;
if (node->CPU_burst.back() == 0)
{
node->CPU_burst.pop_back();
node->time_on = 0;
queue2->Dequeue();
IO->Enqueue(node);
}
else if (node->time_on > 14)
{
node->priority++;
queue2->Dequeue();
fcfs->Enqueue(node);
node->time_on = 0;
}
}
<commit_msg>Phase 2 solved IO. P9 Problems<commit_after>#include "cpuMLFQ.h"
void MLFQ::start()
{
init();
do {
/*thread docpu(&MLFQ::do_CPU, this);
thread doio(&MLFQ::do_IO, this);
doio.join();
docpu.join();*/
do_CPU();
if (!IO->empty())
do_IO();
if (CPUnode != 0 && CPUnode->CPU_burst.back() <= 0)
{
CPUnode->CPU_burst.pop_back();
CPUnode->time_on = 0;
CPUnode->qu = "";
IO->Enqueue(CPUnode);
CPUnode = 0;
}
} while (!queue1->empty() || !queue2->empty() || !fcfs->empty() || !IO->empty());
}
void MLFQ::init()
{
shared_ptr<qnode> P1 = make_shared<qnode>(); //{ 18, 41, 16, 52, 19, 31, 14, 33, 17, 43, 19, 66, 14, 39, 17 }
shared_ptr<qnode> P2 = make_shared<qnode>(); //{ 8, 32, 7, 42, 6, 27, 17, 41, 7, 33, 11, 43, 12, 32, 14 }
shared_ptr<qnode> P3 = make_shared<qnode>(); //{ 6, 51, 5, 53, 6, 46, 9, 32, 11, 52, 4, 61, 8 }
shared_ptr<qnode> P4 = make_shared<qnode>(); //{ 25, 35, 19, 41, 21, 45, 18, 51, 12, 61, 24, 54, 23, 61, 21 }
shared_ptr<qnode> P5 = make_shared<qnode>(); //{ 15, 61, 16, 52, 15, 71, 13, 41, 15, 62, 14, 31, 14, 41, 13, 32, 15 }
shared_ptr<qnode> P6 = make_shared<qnode>(); //{ 6, 25, 5, 31, 6, 32, 5, 41, 4, 81, 8, 39, 11, 42, 5 }
shared_ptr<qnode> P7 = make_shared<qnode>(); //{ 16, 38, 17, 41, 15, 29, 14, 26, 9, 32, 5, 34, 8, 26, 6, 39, 5 }
shared_ptr<qnode> P8 = make_shared<qnode>(); //{5, 52, 4, 42, 6, 31, 7, 21, 4, 43, 5, 31, 7, 32, 6, 32, 7, 41, 4}
shared_ptr<qnode> P9 = make_shared<qnode>(); //{ 11, 37, 12, 41, 6, 41, 4, 48, 6, 41, 5, 29, 4, 26, 5, 31, 3 }
P1->CPU_burst = { 17, 14, 19, 17, 14, 19, 16, 18 };
P1->IO_time = { 39, 66, 43, 33, 31, 52, 41 };
P2->CPU_burst = { 14, 12, 11, 7, 17, 6, 7, 8 };
P2->IO_time = { 32, 43, 41, 27, 42, 32 };
P3->CPU_burst = { 8, 4, 11, 9, 6, 5, 6 };
P3->IO_time = { 61,52,32,46,53,51 };
P4->CPU_burst = { 21,23,24,12,18,21,19,25 };
P4->IO_time = { 61, 54, 61, 51, 45, 41, 35 };
P5->CPU_burst = { 15,13,14,14,15,13,15,16,15 };
P5->IO_time = { 32, 41, 31, 62, 41, 71, 52, 61 };
P6->CPU_burst = { 5, 11, 8, 4, 5, 6, 5, 6 };
P6->IO_time = { 42, 39, 81, 41, 32, 31, 25 };
P7->CPU_burst = { 5, 6, 8, 5, 9, 14, 15, 17, 16 };
P7->IO_time = { 39, 26, 34, 32, 26, 29, 41, 38 };
P8->CPU_burst = { 4, 7, 6, 7, 5, 4, 7, 6, 4, 5 };
P8->IO_time = { 41, 32, 32, 31, 43, 21, 31, 42, 52 };
P9->CPU_burst = { 3, 5, 4, 5, 6, 4, 6, 12, 11 };
P9->IO_time = { 31, 26, 29, 41, 48, 41, 41, 37 };
P1->name = "P1";
P2->name = "P2";
P3->name = "P3";
P4->name = "P4";
P5->name = "P5";
P6->name = "P6";
P7->name = "P7";
P8->name = "P8";
P9->name = "P9";
queue1->Enqueue(P1);
queue1->Enqueue(P2);
queue1->Enqueue(P3);
queue1->Enqueue(P4);
queue1->Enqueue(P5);
queue1->Enqueue(P6);
queue1->Enqueue(P7);
queue1->Enqueue(P8);
queue1->Enqueue(P9);
}
void MLFQ::print()
{
cout << ".................................................." << endl << endl;
cout << "Ready Queue:\tProcess\t\tBurst\t\tQueue" << endl;
shared_ptr<qnode> newNode = queue1->get_front();
while (newNode != 0)
{
cout << "\t\t" << newNode->name << "\t\t" << newNode->CPU_burst.back() << "\t\t" << newNode->qu << endl;
newNode = newNode->next;
}
newNode = queue2->get_front();
while (newNode != 0)
{
cout << "\t\t" << newNode->name << "\t\t" << newNode->CPU_burst.back() << "\t\t" << newNode->qu << endl;
newNode = newNode->next;
}
newNode = fcfs->get_front();
while (newNode != 0)
{
cout << "\t\t" << newNode->name << "\t\t" << newNode->CPU_burst.back() << "\t\t" << newNode->qu << endl;
newNode = newNode->next;
}
cout << ".................................................." << endl << endl;
cout << "Now in IO:\tProcess\t\tRemaining I/O time\n" << IO;
cout << endl;
}
void MLFQ::CPU_time_quantom_7()
{
if (CPUnode == 0) {
CPUnode = queue1->get_front();
queue1->Dequeue();
cout << "Current time: " << counter << "\nCurrently Running: " << CPUnode->name << endl;
print();
}
CPUnode->CPU_burst.back()--;
CPUnode->time_on++;
if (CPUnode->time_on == 7)
{
CPUnode->priority++;
CPUnode->qu = "Q2";
queue2->Enqueue(CPUnode);
CPUnode->time_on = 0;
CPUnode = 0;
}
}
void MLFQ::CPU_fcfs()
{
if (CPUnode == 0) {
CPUnode = fcfs->get_front();
fcfs->Dequeue();
cout << "Current time: " << counter << "\nCurrently Running: " << CPUnode->name << endl;
print();
}
CPUnode->CPU_burst.back()--;
CPUnode->time_on++;
}
void MLFQ::do_IO()
{
shared_ptr<qnode> nodeParent = 0;
shared_ptr<qnode> node = IO->get_front();
while (node != 0)
{
node->IO_time.back()--;
if (node->IO_time.back() == 0)
{
IO->remove_node(node);
switch (node->priority)
{
case 1:
node->qu = "Q1";
queue1->Enqueue(node);
break;
case 2:
node->qu = "Q2";
queue2->Enqueue(node);
break;
case 3:
node->qu = "FCFS";
fcfs->Enqueue(node);
break;
default:
cout << "error\n";
break;
}
node->IO_time.pop_back();
}
node = node->next;
}
}
void MLFQ::do_CPU()
{
if (!queue1->empty())
{
CPU_time_quantom_7();
}
else if (!queue2->empty())
{
CPU_time_quantom_14();
}
else if (!fcfs->empty())
{
CPU_fcfs();
}
else
cout << "CPU Idle";
counter++;
}
void MLFQ::CPU_time_quantom_14()
{
if (CPUnode == 0)
{
CPUnode = queue2->get_front();
queue2->Dequeue();
cout << "Current time: " << counter << "\nCurrently Running: " << CPUnode->name << endl;
print();
}
CPUnode->CPU_burst.back()--;
CPUnode->time_on++;
if (CPUnode->time_on > 14)
{
CPUnode->priority++;
fcfs->Enqueue(CPUnode);
CPUnode->time_on = 0;
CPUnode = 0;
}
}
<|endoftext|> |
<commit_before>#include "stdafx.h"
#include "EasyServer.h"
#include "Config.h"
#include "PacketType.h"
#include "Exception.h"
#include "ClientSession.h"
#include "ClientManager.h"
#include "DatabaseJobManager.h"
#include "DbHelper.h"
#pragma comment(lib,"ws2_32.lib")
SOCKET g_AcceptedSocket = NULL ;
__declspec(thread) int LThreadType = -1 ;
int _tmain(int argc, _TCHAR* argv[])
{
/// crash dump ؼ
SetUnhandledExceptionFilter(ExceptionFilter) ;
LThreadType = THREAD_MAIN ;
/// Manager Init
GClientManager = new ClientManager ;
GDatabaseJobManager = new DatabaseJobManager ;
GPlayerManager = new PlayerManager;
/// DB Helper ʱȭ
if ( false == DbHelper::Initialize(DB_CONN_STR) )
return -1 ;
/// ʱȭ
WSADATA wsa ;
if (WSAStartup(MAKEWORD(2,2), &wsa) != 0)
return -1 ;
SOCKET listenSocket = socket(AF_INET, SOCK_STREAM, 0) ;
if (listenSocket == INVALID_SOCKET)
return -1 ;
int opt = 1 ;
::setsockopt(listenSocket, SOL_SOCKET, SO_REUSEADDR, (const char*)&opt, sizeof(int) ) ;
/// bind
SOCKADDR_IN serveraddr ;
ZeroMemory(&serveraddr, sizeof(serveraddr)) ;
serveraddr.sin_family = AF_INET ;
serveraddr.sin_port = htons(LISTEN_PORT) ;
serveraddr.sin_addr.s_addr = htonl(INADDR_ANY) ;
int ret = bind(listenSocket, (SOCKADDR*)&serveraddr, sizeof(serveraddr)) ;
if (ret == SOCKET_ERROR)
return -1 ;
/// listen
ret = listen(listenSocket, SOMAXCONN) ;
if (ret == SOCKET_ERROR)
return -1 ;
/// auto-reset event
HANDLE hEvent = CreateEvent(NULL, FALSE, FALSE, NULL) ;
if (hEvent == NULL)
return -1 ;
/// I/O Thread
DWORD dwThreadId ;
HANDLE hThread = (HANDLE)_beginthreadex (NULL, 0, ClientHandlingThread, hEvent, 0, (unsigned int*)&dwThreadId) ;
if (hThread == NULL)
return -1 ;
/// DB Thread
HANDLE hDbThread = (HANDLE)_beginthreadex (NULL, 0, DatabaseHandlingThread, NULL, 0, (unsigned int*)&dwThreadId) ;
if (hDbThread == NULL)
return -1 ;
/// accept loop
while ( true )
{
g_AcceptedSocket = accept(listenSocket, NULL, NULL) ;
if ( g_AcceptedSocket == INVALID_SOCKET )
{
printf("accept: invalid socket\n") ;
continue ;
}
/// accept event fire!
if ( !SetEvent(hEvent) )
{
printf("SetEvent error: %d\n",GetLastError()) ;
break ;
}
}
CloseHandle( hThread ) ;
CloseHandle( hEvent ) ;
CloseHandle( hDbThread ) ;
//
WSACleanup() ;
DbHelper::Finalize() ;
delete GClientManager ;
delete GDatabaseJobManager ;
return 0 ;
}
unsigned int WINAPI ClientHandlingThread( LPVOID lpParam )
{
LThreadType = THREAD_CLIENT ;
HANDLE hEvent = (HANDLE)lpParam ;
/// Timer
HANDLE hTimer = CreateWaitableTimer(NULL, FALSE, NULL) ;
if (hTimer == NULL)
return -1 ;
LARGE_INTEGER liDueTime ;
liDueTime.QuadPart = -10000000 ; ///< 1 ĺ
if ( !SetWaitableTimer(hTimer, &liDueTime, 100, TimerProc, NULL, TRUE) )
return -1 ;
while ( true )
{
/// accept or IO/Timer completion
DWORD result = WaitForSingleObjectEx(hEvent, INFINITE, TRUE) ;
/// client connected
if ( result == WAIT_OBJECT_0 )
{
/// ü Ҵ ʱȭ
ClientSession* client = GClientManager->CreateClient(g_AcceptedSocket) ;
SOCKADDR_IN clientaddr ;
int addrlen = sizeof(clientaddr) ;
getpeername(g_AcceptedSocket, (SOCKADDR*)&clientaddr, &addrlen) ;
// Ŭ ó
if ( false == client->OnConnect(&clientaddr) )
{
client->Disconnect() ;
}
continue ; ///< ٽ
}
// APC ִ completion ƴ϶
if ( result != WAIT_IO_COMPLETION )
return -1 ;
}
CloseHandle( hTimer ) ;
return 0;
}
unsigned int WINAPI DatabaseHandlingThread( LPVOID lpParam )
{
LThreadType = THREAD_DATABASE ;
while ( true )
{
/// ⺻ polling ϸ鼭 Job ִٸ ó ϴ
GDatabaseJobManager->ExecuteDatabaseJobs() ;
Sleep(1) ;
}
return 0 ;
}
void CALLBACK TimerProc(LPVOID lpArg, DWORD dwTimerLowValue, DWORD dwTimerHighValue)
{
assert( LThreadType == THREAD_CLIENT ) ;
GClientManager->OnPeriodWork() ;
}
<commit_msg>* Change Include EasyServer -> Main<commit_after>#include "stdafx.h"
#include "Main.h"
#include "Config.h"
#include "PacketType.h"
#include "Exception.h"
#include "ClientSession.h"
#include "ClientManager.h"
#include "DatabaseJobManager.h"
#include "DbHelper.h"
#pragma comment(lib,"ws2_32.lib")
SOCKET g_AcceptedSocket = NULL ;
__declspec(thread) int LThreadType = -1 ;
int _tmain(int argc, _TCHAR* argv[])
{
/// crash dump ؼ
SetUnhandledExceptionFilter(ExceptionFilter) ;
LThreadType = THREAD_MAIN ;
/// Manager Init
GClientManager = new ClientManager ;
GDatabaseJobManager = new DatabaseJobManager ;
GPlayerManager = new PlayerManager;
/// DB Helper ʱȭ
if ( false == DbHelper::Initialize(DB_CONN_STR) )
return -1 ;
/// ʱȭ
WSADATA wsa ;
if (WSAStartup(MAKEWORD(2,2), &wsa) != 0)
return -1 ;
SOCKET listenSocket = socket(AF_INET, SOCK_STREAM, 0) ;
if (listenSocket == INVALID_SOCKET)
return -1 ;
int opt = 1 ;
::setsockopt(listenSocket, SOL_SOCKET, SO_REUSEADDR, (const char*)&opt, sizeof(int) ) ;
/// bind
SOCKADDR_IN serveraddr ;
ZeroMemory(&serveraddr, sizeof(serveraddr)) ;
serveraddr.sin_family = AF_INET ;
serveraddr.sin_port = htons(LISTEN_PORT) ;
serveraddr.sin_addr.s_addr = htonl(INADDR_ANY) ;
int ret = bind(listenSocket, (SOCKADDR*)&serveraddr, sizeof(serveraddr)) ;
if (ret == SOCKET_ERROR)
return -1 ;
/// listen
ret = listen(listenSocket, SOMAXCONN) ;
if (ret == SOCKET_ERROR)
return -1 ;
/// auto-reset event
HANDLE hEvent = CreateEvent(NULL, FALSE, FALSE, NULL) ;
if (hEvent == NULL)
return -1 ;
/// I/O Thread
DWORD dwThreadId ;
HANDLE hThread = (HANDLE)_beginthreadex (NULL, 0, ClientHandlingThread, hEvent, 0, (unsigned int*)&dwThreadId) ;
if (hThread == NULL)
return -1 ;
/// DB Thread
HANDLE hDbThread = (HANDLE)_beginthreadex (NULL, 0, DatabaseHandlingThread, NULL, 0, (unsigned int*)&dwThreadId) ;
if (hDbThread == NULL)
return -1 ;
/// accept loop
while ( true )
{
g_AcceptedSocket = accept(listenSocket, NULL, NULL) ;
if ( g_AcceptedSocket == INVALID_SOCKET )
{
printf("accept: invalid socket\n") ;
continue ;
}
/// accept event fire!
if ( !SetEvent(hEvent) )
{
printf("SetEvent error: %d\n",GetLastError()) ;
break ;
}
}
CloseHandle( hThread ) ;
CloseHandle( hEvent ) ;
CloseHandle( hDbThread ) ;
//
WSACleanup() ;
DbHelper::Finalize() ;
delete GClientManager ;
delete GDatabaseJobManager ;
return 0 ;
}
unsigned int WINAPI ClientHandlingThread( LPVOID lpParam )
{
LThreadType = THREAD_CLIENT ;
HANDLE hEvent = (HANDLE)lpParam ;
/// Timer
HANDLE hTimer = CreateWaitableTimer(NULL, FALSE, NULL) ;
if (hTimer == NULL)
return -1 ;
LARGE_INTEGER liDueTime ;
liDueTime.QuadPart = -10000000 ; ///< 1 ĺ
if ( !SetWaitableTimer(hTimer, &liDueTime, 100, TimerProc, NULL, TRUE) )
return -1 ;
while ( true )
{
/// accept or IO/Timer completion
DWORD result = WaitForSingleObjectEx(hEvent, INFINITE, TRUE) ;
/// client connected
if ( result == WAIT_OBJECT_0 )
{
/// ü Ҵ ʱȭ
ClientSession* client = GClientManager->CreateClient(g_AcceptedSocket) ;
SOCKADDR_IN clientaddr ;
int addrlen = sizeof(clientaddr) ;
getpeername(g_AcceptedSocket, (SOCKADDR*)&clientaddr, &addrlen) ;
// Ŭ ó
if ( false == client->OnConnect(&clientaddr) )
{
client->Disconnect() ;
}
continue ; ///< ٽ
}
// APC ִ completion ƴ϶
if ( result != WAIT_IO_COMPLETION )
return -1 ;
}
CloseHandle( hTimer ) ;
return 0;
}
unsigned int WINAPI DatabaseHandlingThread( LPVOID lpParam )
{
LThreadType = THREAD_DATABASE ;
while ( true )
{
/// ⺻ polling ϸ鼭 Job ִٸ ó ϴ
GDatabaseJobManager->ExecuteDatabaseJobs() ;
Sleep(1) ;
}
return 0 ;
}
void CALLBACK TimerProc(LPVOID lpArg, DWORD dwTimerLowValue, DWORD dwTimerHighValue)
{
assert( LThreadType == THREAD_CLIENT ) ;
GClientManager->OnPeriodWork() ;
}
<|endoftext|> |
<commit_before>// Regression test for
// https://code.google.com/p/address-sanitizer/issues/detail?id=183
// RUN: %clangxx_asan -O2 %s -o %t
// RUN: not %run %t 12 2>&1 | FileCheck %s
// RUN: not %run %t 100 2>&1 | FileCheck %s
// RUN: not %run %t 10000 2>&1 | FileCheck %s
#include <stdlib.h>
#include <string.h>
int main(int argc, char *argv[]) {
int *x = new int[5];
memset(x, 0, sizeof(x[0]) * 5);
int index = atoi(argv[1]);
int res = x[index];
// CHECK: AddressSanitizer: {{(heap-buffer-overflow|SEGV)}}
// CHECK: #0 0x{{.*}} in main {{.*}}heap-overflow-large.cc:[[@LINE-2]]
// CHECK: AddressSanitizer can not {{(provide additional info|describe address in more detail \(wild memory access suspected\))}}
// CHECK: SUMMARY: AddressSanitizer: {{(heap-buffer-overflow|SEGV)}}
delete[] x;
return res;
}
<commit_msg>[asan] Fix a flaky test.<commit_after>// Regression test for
// https://code.google.com/p/address-sanitizer/issues/detail?id=183
// RUN: %clangxx_asan -O2 %s -o %t
// RUN: not %run %t 12 2>&1 | FileCheck %s
// RUN: not %run %t 100 2>&1 | FileCheck %s
// RUN: not %run %t 10000 2>&1 | FileCheck %s
#include <stdlib.h>
#include <string.h>
#include <stdio.h>
int main(int argc, char *argv[]) {
fprintf(stderr, "main\n");
int *x = new int[5];
memset(x, 0, sizeof(x[0]) * 5);
int index = atoi(argv[1]);
int res = x[index];
// CHECK: main
// CHECK-NOT: CHECK failed
delete[] x;
return res ? res : 1;
}
<|endoftext|> |
<commit_before>// Licensed to the Apache Software Foundation (ASF) under one
// or more contributor license agreements. See the NOTICE file
// distributed with this work for additional information
// regarding copyright ownership. The ASF licenses this file
// to you under the Apache License, Version 2.0 (the
// "License"); you may not use this file except in compliance
// with the License. You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <stdlib.h>
#include <sstream>
#include <vector>
#include <glog/logging.h>
#include <mesos/mesos.hpp>
#include <mesos/resources.hpp>
#include <mesos/scheduler.hpp>
#include <mesos/type_utils.hpp>
#include <mesos/authorizer/acls.hpp>
#include <stout/flags.hpp>
#include <stout/json.hpp>
#include <stout/option.hpp>
#include <stout/os.hpp>
#include <stout/protobuf.hpp>
#include <stout/stringify.hpp>
#include <stout/uuid.hpp>
#include "common/status_utils.hpp"
#include "logging/flags.hpp"
#include "logging/logging.hpp"
using namespace mesos;
using namespace mesos::internal;
using std::cerr;
using std::cout;
using std::endl;
using std::ostringstream;
using std::string;
using std::vector;
// TODO(jieyu): Currently, persistent volume is only allowed for
// reserved resources.
static Resources SHARD_INITIAL_RESOURCES(const string& role)
{
return Resources::parse("cpus:0.1;mem:32;disk:16", role).get();
}
static Resource SHARD_PERSISTENT_VOLUME(
const string& role,
const string& persistenceId,
const string& containerPath,
const string& principal)
{
Volume volume;
volume.set_container_path(containerPath);
volume.set_mode(Volume::RW);
Resource::DiskInfo info;
info.mutable_persistence()->set_id(persistenceId);
info.mutable_persistence()->set_principal(principal);
info.mutable_volume()->CopyFrom(volume);
Resource resource = Resources::parse("disk", "8", role).get();
resource.mutable_disk()->CopyFrom(info);
return resource;
}
static Offer::Operation CREATE(const Resources& volumes)
{
Offer::Operation operation;
operation.set_type(Offer::Operation::CREATE);
operation.mutable_create()->mutable_volumes()->CopyFrom(volumes);
return operation;
}
static Offer::Operation LAUNCH(const vector<TaskInfo>& tasks)
{
Offer::Operation operation;
operation.set_type(Offer::Operation::LAUNCH);
foreach (const TaskInfo& task, tasks) {
operation.mutable_launch()->add_task_infos()->CopyFrom(task);
}
return operation;
}
// The framework launches a task on each registered slave using a
// persistent volume. It restarts the task once the previous one on
// the slave finishes. The framework terminates once the number of
// tasks launched on each slave reaches a limit.
class PersistentVolumeScheduler : public Scheduler
{
public:
PersistentVolumeScheduler(
const FrameworkInfo& _frameworkInfo,
size_t numShards,
size_t tasksPerShard)
: frameworkInfo(_frameworkInfo)
{
for (size_t i = 0; i < numShards; i++) {
shards.push_back(Shard(
"shard-" + stringify(i),
frameworkInfo.role(),
tasksPerShard));
}
}
virtual void registered(
SchedulerDriver* driver,
const FrameworkID& frameworkId,
const MasterInfo& masterInfo)
{
LOG(INFO) << "Registered with master " << masterInfo
<< " and got framework ID " << frameworkId;
frameworkInfo.mutable_id()->CopyFrom(frameworkId);
}
virtual void reregistered(
SchedulerDriver* driver,
const MasterInfo& masterInfo)
{
LOG(INFO) << "Reregistered with master " << masterInfo;
}
virtual void disconnected(
SchedulerDriver* driver)
{
LOG(INFO) << "Disconnected!";
}
virtual void resourceOffers(
SchedulerDriver* driver,
const vector<Offer>& offers)
{
foreach (const Offer& offer, offers) {
LOG(INFO) << "Received offer " << offer.id() << " from agent "
<< offer.slave_id() << " (" << offer.hostname() << ") "
<< "with " << offer.resources();
Resources offered = offer.resources();
// The operation we will perform on the offer.
vector<Offer::Operation> operations;
foreach (Shard& shard, shards) {
switch (shard.state) {
case Shard::INIT:
if (offered.contains(shard.resources)) {
Resource volume = SHARD_PERSISTENT_VOLUME(
frameworkInfo.role(),
UUID::random().toString(),
"volume",
frameworkInfo.principal());
Try<Resources> resources = shard.resources.apply(CREATE(volume));
CHECK_SOME(resources);
TaskInfo task;
task.set_name(shard.name);
task.mutable_task_id()->set_value(UUID::random().toString());
task.mutable_slave_id()->CopyFrom(offer.slave_id());
task.mutable_resources()->CopyFrom(resources.get());
task.mutable_command()->set_value("touch volume/persisted");
// Update the shard.
shard.state = Shard::STAGING;
shard.taskId = task.task_id();
shard.volume.id = volume.disk().persistence().id();
shard.volume.slave = offer.slave_id().value();
shard.resources = resources.get();
shard.launched++;
operations.push_back(CREATE(volume));
operations.push_back(LAUNCH({task}));
resources = offered.apply(vector<Offer::Operation>{
CREATE(volume),
LAUNCH({task})});
CHECK_SOME(resources);
offered = resources.get();
}
break;
case Shard::WAITING:
if (offered.contains(shard.resources)) {
CHECK_EQ(shard.volume.slave, offer.slave_id().value());
TaskInfo task;
task.set_name(shard.name);
task.mutable_task_id()->set_value(UUID::random().toString());
task.mutable_slave_id()->CopyFrom(offer.slave_id());
task.mutable_resources()->CopyFrom(shard.resources);
task.mutable_command()->set_value("test -f volume/persisted");
// Update the shard.
shard.state = Shard::STAGING;
shard.taskId = task.task_id();
shard.launched++;
operations.push_back(LAUNCH({task}));
}
break;
case Shard::STAGING:
case Shard::RUNNING:
case Shard::DONE:
// Ignore the offer.
break;
default:
LOG(ERROR) << "Unexpected shard state: " << shard.state;
driver->abort();
break;
}
}
driver->acceptOffers({offer.id()}, operations);
}
}
virtual void offerRescinded(
SchedulerDriver* driver,
const OfferID& offerId)
{
LOG(INFO) << "Offer " << offerId << " has been rescinded";
}
virtual void statusUpdate(
SchedulerDriver* driver,
const TaskStatus& status)
{
LOG(INFO) << "Task '" << status.task_id() << "' is in state "
<< status.state();
foreach (Shard& shard, shards) {
if (shard.taskId == status.task_id()) {
switch (status.state()) {
case TASK_RUNNING:
shard.state = Shard::RUNNING;
break;
case TASK_FINISHED:
if (shard.launched >= shard.tasks) {
shard.state = Shard::DONE;
} else {
shard.state = Shard::WAITING;
}
break;
case TASK_STAGING:
case TASK_STARTING:
// Ignore the status update.
break;
default:
LOG(ERROR) << "Unexpected task state " << status.state()
<< " for task '" << status.task_id() << "'";
driver->abort();
break;
}
break;
}
}
// Check the terminal condition.
bool terminal = true;
foreach (const Shard& shard, shards) {
if (shard.state != Shard::DONE) {
terminal = false;
break;
}
}
if (terminal) {
driver->stop();
}
}
virtual void frameworkMessage(
SchedulerDriver* driver,
const ExecutorID& executorId,
const SlaveID& slaveId,
const string& data)
{
LOG(INFO) << "Received framework message from executor '" << executorId
<< "' on agent " << slaveId << ": '" << data << "'";
}
virtual void slaveLost(
SchedulerDriver* driver,
const SlaveID& slaveId)
{
LOG(INFO) << "Lost agent " << slaveId;
}
virtual void executorLost(
SchedulerDriver* driver,
const ExecutorID& executorId,
const SlaveID& slaveId,
int status)
{
LOG(INFO) << "Lost executor '" << executorId << "' on agent "
<< slaveId << ", " << WSTRINGIFY(status);
}
virtual void error(
SchedulerDriver* driver,
const string& message)
{
LOG(ERROR) << message;
}
private:
struct Shard
{
enum State
{
INIT = 0, // The shard hasn't been launched yet.
STAGING, // The shard has been launched.
RUNNING, // The shard is running.
WAITING, // The shard is waiting to be re-launched.
DONE, // The shard has finished all tasks.
// TODO(jieyu): Add another state so that we can track the
// destroy of the volume once all tasks finish.
};
// The persistent volume associated with this shard.
struct Volume
{
// The persistence ID.
string id;
// An identifier used to uniquely identify a slave (even across
// reboot). In the test, we use the slave ID since slaves will not
// be rebooted. Note that we cannot use hostname as the identifier
// in a local cluster because all slaves share the same hostname.
string slave;
};
Shard(const string& _name, const string& role, size_t _tasks)
: name(_name),
state(INIT),
resources(SHARD_INITIAL_RESOURCES(role)),
launched(0),
tasks(_tasks) {}
string name;
State state; // The current state of this shard.
TaskID taskId; // The ID of the current task.
Volume volume; // The persistent volume associated with the shard.
Resources resources; // Resources required to launch the shard.
size_t launched; // How many tasks this shard has launched.
size_t tasks; // How many tasks this shard should launch.
};
FrameworkInfo frameworkInfo;
vector<Shard> shards;
};
class Flags : public logging::Flags
{
public:
Flags()
{
add(&master,
"master",
"The master to connect to. May be one of:\n"
" master@addr:port (The PID of the master)\n"
" zk://host1:port1,host2:port2,.../path\n"
" zk://username:password@host1:port1,host2:port2,.../path\n"
" file://path/to/file (where file contains one of the above)");
add(&role,
"role",
"Role to use when registering",
"test");
add(&principal,
"principal",
"The principal used to identify this framework",
"test");
add(&num_shards,
"num_shards",
"The number of shards the framework will run.",
3);
add(&tasks_per_shard,
"tasks_per_shard",
"The number of tasks should be launched per shard.",
3);
}
Option<string> master;
string role;
string principal;
size_t num_shards;
size_t tasks_per_shard;
};
int main(int argc, char** argv)
{
Flags flags;
Try<flags::Warnings> load = flags.load("MESOS_", argc, argv);
if (load.isError()) {
cerr << flags.usage(load.error()) << endl;
return EXIT_FAILURE;
}
if (flags.help) {
cout << flags.usage() << endl;
return EXIT_SUCCESS;
}
if (flags.master.isNone()) {
cerr << flags.usage("Missing required option --master") << endl;
return EXIT_FAILURE;
}
logging::initialize(argv[0], flags, true); // Catch signals.
// Log any flag warnings (after logging is initialized).
foreach (const flags::Warning& warning, load->warnings) {
LOG(WARNING) << warning.message;
}
FrameworkInfo framework;
framework.set_user(""); // Have Mesos fill in the current user.
framework.set_name("Persistent Volume Framework (C++)");
framework.set_role(flags.role);
framework.set_checkpoint(true);
framework.set_principal(flags.principal);
if (flags.master.get() == "local") {
// Configure master.
os::setenv("MESOS_ROLES", flags.role);
os::setenv("MESOS_AUTHENTICATE_FRAMEWORKS", "false");
ACLs acls;
ACL::RegisterFramework* acl = acls.add_register_frameworks();
acl->mutable_principals()->set_type(ACL::Entity::ANY);
acl->mutable_roles()->add_values(flags.role);
os::setenv("MESOS_ACLS", stringify(JSON::protobuf(acls)));
// Configure slave.
os::setenv("MESOS_DEFAULT_ROLE", flags.role);
}
PersistentVolumeScheduler scheduler(
framework,
flags.num_shards,
flags.tasks_per_shard);
MesosSchedulerDriver* driver = new MesosSchedulerDriver(
&scheduler,
framework,
flags.master.get());
int status = driver->run() == DRIVER_STOPPED ? EXIT_SUCCESS : EXIT_FAILURE;
driver->stop();
delete driver;
return status;
}
<commit_msg>Sped up ExamplesTest.PersistentVolumeFramework.<commit_after>// Licensed to the Apache Software Foundation (ASF) under one
// or more contributor license agreements. See the NOTICE file
// distributed with this work for additional information
// regarding copyright ownership. The ASF licenses this file
// to you under the Apache License, Version 2.0 (the
// "License"); you may not use this file except in compliance
// with the License. You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <stdlib.h>
#include <sstream>
#include <vector>
#include <glog/logging.h>
#include <mesos/mesos.hpp>
#include <mesos/resources.hpp>
#include <mesos/scheduler.hpp>
#include <mesos/type_utils.hpp>
#include <mesos/authorizer/acls.hpp>
#include <stout/flags.hpp>
#include <stout/json.hpp>
#include <stout/option.hpp>
#include <stout/os.hpp>
#include <stout/protobuf.hpp>
#include <stout/stringify.hpp>
#include <stout/uuid.hpp>
#include "common/status_utils.hpp"
#include "logging/flags.hpp"
#include "logging/logging.hpp"
using namespace mesos;
using namespace mesos::internal;
using std::cerr;
using std::cout;
using std::endl;
using std::ostringstream;
using std::string;
using std::vector;
// TODO(jieyu): Currently, persistent volume is only allowed for
// reserved resources.
static Resources SHARD_INITIAL_RESOURCES(const string& role)
{
return Resources::parse("cpus:0.1;mem:32;disk:16", role).get();
}
static Resource SHARD_PERSISTENT_VOLUME(
const string& role,
const string& persistenceId,
const string& containerPath,
const string& principal)
{
Volume volume;
volume.set_container_path(containerPath);
volume.set_mode(Volume::RW);
Resource::DiskInfo info;
info.mutable_persistence()->set_id(persistenceId);
info.mutable_persistence()->set_principal(principal);
info.mutable_volume()->CopyFrom(volume);
Resource resource = Resources::parse("disk", "8", role).get();
resource.mutable_disk()->CopyFrom(info);
return resource;
}
static Offer::Operation CREATE(const Resources& volumes)
{
Offer::Operation operation;
operation.set_type(Offer::Operation::CREATE);
operation.mutable_create()->mutable_volumes()->CopyFrom(volumes);
return operation;
}
static Offer::Operation LAUNCH(const vector<TaskInfo>& tasks)
{
Offer::Operation operation;
operation.set_type(Offer::Operation::LAUNCH);
foreach (const TaskInfo& task, tasks) {
operation.mutable_launch()->add_task_infos()->CopyFrom(task);
}
return operation;
}
// The framework launches a task on each registered slave using a
// persistent volume. It restarts the task once the previous one on
// the slave finishes. The framework terminates once the number of
// tasks launched on each slave reaches a limit.
class PersistentVolumeScheduler : public Scheduler
{
public:
PersistentVolumeScheduler(
const FrameworkInfo& _frameworkInfo,
size_t numShards,
size_t tasksPerShard)
: frameworkInfo(_frameworkInfo)
{
for (size_t i = 0; i < numShards; i++) {
shards.push_back(Shard(
"shard-" + stringify(i),
frameworkInfo.role(),
tasksPerShard));
}
}
virtual void registered(
SchedulerDriver* driver,
const FrameworkID& frameworkId,
const MasterInfo& masterInfo)
{
LOG(INFO) << "Registered with master " << masterInfo
<< " and got framework ID " << frameworkId;
frameworkInfo.mutable_id()->CopyFrom(frameworkId);
}
virtual void reregistered(
SchedulerDriver* driver,
const MasterInfo& masterInfo)
{
LOG(INFO) << "Reregistered with master " << masterInfo;
}
virtual void disconnected(
SchedulerDriver* driver)
{
LOG(INFO) << "Disconnected!";
}
virtual void resourceOffers(
SchedulerDriver* driver,
const vector<Offer>& offers)
{
foreach (const Offer& offer, offers) {
LOG(INFO) << "Received offer " << offer.id() << " from agent "
<< offer.slave_id() << " (" << offer.hostname() << ") "
<< "with " << offer.resources();
Resources offered = offer.resources();
// The operation we will perform on the offer.
vector<Offer::Operation> operations;
foreach (Shard& shard, shards) {
switch (shard.state) {
case Shard::INIT:
if (offered.contains(shard.resources)) {
Resource volume = SHARD_PERSISTENT_VOLUME(
frameworkInfo.role(),
UUID::random().toString(),
"volume",
frameworkInfo.principal());
Try<Resources> resources = shard.resources.apply(CREATE(volume));
CHECK_SOME(resources);
TaskInfo task;
task.set_name(shard.name);
task.mutable_task_id()->set_value(UUID::random().toString());
task.mutable_slave_id()->CopyFrom(offer.slave_id());
task.mutable_resources()->CopyFrom(resources.get());
task.mutable_command()->set_value("touch volume/persisted");
// Update the shard.
shard.state = Shard::STAGING;
shard.taskId = task.task_id();
shard.volume.id = volume.disk().persistence().id();
shard.volume.slave = offer.slave_id().value();
shard.resources = resources.get();
shard.launched++;
operations.push_back(CREATE(volume));
operations.push_back(LAUNCH({task}));
resources = offered.apply(vector<Offer::Operation>{
CREATE(volume),
LAUNCH({task})});
CHECK_SOME(resources);
offered = resources.get();
}
break;
case Shard::WAITING:
if (offered.contains(shard.resources)) {
CHECK_EQ(shard.volume.slave, offer.slave_id().value());
TaskInfo task;
task.set_name(shard.name);
task.mutable_task_id()->set_value(UUID::random().toString());
task.mutable_slave_id()->CopyFrom(offer.slave_id());
task.mutable_resources()->CopyFrom(shard.resources);
task.mutable_command()->set_value("test -f volume/persisted");
// Update the shard.
shard.state = Shard::STAGING;
shard.taskId = task.task_id();
shard.launched++;
operations.push_back(LAUNCH({task}));
}
break;
case Shard::STAGING:
case Shard::RUNNING:
case Shard::DONE:
// Ignore the offer.
break;
default:
LOG(ERROR) << "Unexpected shard state: " << shard.state;
driver->abort();
break;
}
}
driver->acceptOffers({offer.id()}, operations);
}
}
virtual void offerRescinded(
SchedulerDriver* driver,
const OfferID& offerId)
{
LOG(INFO) << "Offer " << offerId << " has been rescinded";
}
virtual void statusUpdate(
SchedulerDriver* driver,
const TaskStatus& status)
{
LOG(INFO) << "Task '" << status.task_id() << "' is in state "
<< status.state();
foreach (Shard& shard, shards) {
if (shard.taskId == status.task_id()) {
switch (status.state()) {
case TASK_RUNNING:
shard.state = Shard::RUNNING;
break;
case TASK_FINISHED:
if (shard.launched >= shard.tasks) {
shard.state = Shard::DONE;
} else {
shard.state = Shard::WAITING;
}
break;
case TASK_STAGING:
case TASK_STARTING:
// Ignore the status update.
break;
default:
LOG(ERROR) << "Unexpected task state " << status.state()
<< " for task '" << status.task_id() << "'";
driver->abort();
break;
}
break;
}
}
// Check the terminal condition.
bool terminal = true;
foreach (const Shard& shard, shards) {
if (shard.state != Shard::DONE) {
terminal = false;
break;
}
}
if (terminal) {
driver->stop();
}
}
virtual void frameworkMessage(
SchedulerDriver* driver,
const ExecutorID& executorId,
const SlaveID& slaveId,
const string& data)
{
LOG(INFO) << "Received framework message from executor '" << executorId
<< "' on agent " << slaveId << ": '" << data << "'";
}
virtual void slaveLost(
SchedulerDriver* driver,
const SlaveID& slaveId)
{
LOG(INFO) << "Lost agent " << slaveId;
}
virtual void executorLost(
SchedulerDriver* driver,
const ExecutorID& executorId,
const SlaveID& slaveId,
int status)
{
LOG(INFO) << "Lost executor '" << executorId << "' on agent "
<< slaveId << ", " << WSTRINGIFY(status);
}
virtual void error(
SchedulerDriver* driver,
const string& message)
{
LOG(ERROR) << message;
}
private:
struct Shard
{
enum State
{
INIT = 0, // The shard hasn't been launched yet.
STAGING, // The shard has been launched.
RUNNING, // The shard is running.
WAITING, // The shard is waiting to be re-launched.
DONE, // The shard has finished all tasks.
// TODO(jieyu): Add another state so that we can track the
// destroy of the volume once all tasks finish.
};
// The persistent volume associated with this shard.
struct Volume
{
// The persistence ID.
string id;
// An identifier used to uniquely identify a slave (even across
// reboot). In the test, we use the slave ID since slaves will not
// be rebooted. Note that we cannot use hostname as the identifier
// in a local cluster because all slaves share the same hostname.
string slave;
};
Shard(const string& _name, const string& role, size_t _tasks)
: name(_name),
state(INIT),
resources(SHARD_INITIAL_RESOURCES(role)),
launched(0),
tasks(_tasks) {}
string name;
State state; // The current state of this shard.
TaskID taskId; // The ID of the current task.
Volume volume; // The persistent volume associated with the shard.
Resources resources; // Resources required to launch the shard.
size_t launched; // How many tasks this shard has launched.
size_t tasks; // How many tasks this shard should launch.
};
FrameworkInfo frameworkInfo;
vector<Shard> shards;
};
class Flags : public logging::Flags
{
public:
Flags()
{
add(&master,
"master",
"The master to connect to. May be one of:\n"
" master@addr:port (The PID of the master)\n"
" zk://host1:port1,host2:port2,.../path\n"
" zk://username:password@host1:port1,host2:port2,.../path\n"
" file://path/to/file (where file contains one of the above)");
add(&role,
"role",
"Role to use when registering",
"test");
add(&principal,
"principal",
"The principal used to identify this framework",
"test");
add(&num_shards,
"num_shards",
"The number of shards the framework will run.",
3);
add(&tasks_per_shard,
"tasks_per_shard",
"The number of tasks should be launched per shard.",
2);
}
Option<string> master;
string role;
string principal;
size_t num_shards;
size_t tasks_per_shard;
};
int main(int argc, char** argv)
{
Flags flags;
Try<flags::Warnings> load = flags.load("MESOS_", argc, argv);
if (load.isError()) {
cerr << flags.usage(load.error()) << endl;
return EXIT_FAILURE;
}
if (flags.help) {
cout << flags.usage() << endl;
return EXIT_SUCCESS;
}
if (flags.master.isNone()) {
cerr << flags.usage("Missing required option --master") << endl;
return EXIT_FAILURE;
}
logging::initialize(argv[0], flags, true); // Catch signals.
// Log any flag warnings (after logging is initialized).
foreach (const flags::Warning& warning, load->warnings) {
LOG(WARNING) << warning.message;
}
FrameworkInfo framework;
framework.set_user(""); // Have Mesos fill in the current user.
framework.set_name("Persistent Volume Framework (C++)");
framework.set_role(flags.role);
framework.set_checkpoint(true);
framework.set_principal(flags.principal);
if (flags.master.get() == "local") {
// Configure master.
os::setenv("MESOS_ROLES", flags.role);
os::setenv("MESOS_AUTHENTICATE_FRAMEWORKS", "false");
ACLs acls;
ACL::RegisterFramework* acl = acls.add_register_frameworks();
acl->mutable_principals()->set_type(ACL::Entity::ANY);
acl->mutable_roles()->add_values(flags.role);
os::setenv("MESOS_ACLS", stringify(JSON::protobuf(acls)));
// Configure slave.
os::setenv("MESOS_DEFAULT_ROLE", flags.role);
}
PersistentVolumeScheduler scheduler(
framework,
flags.num_shards,
flags.tasks_per_shard);
MesosSchedulerDriver* driver = new MesosSchedulerDriver(
&scheduler,
framework,
flags.master.get());
int status = driver->run() == DRIVER_STOPPED ? EXIT_SUCCESS : EXIT_FAILURE;
driver->stop();
delete driver;
return status;
}
<|endoftext|> |
<commit_before>#ifndef KDEINETLAYER_HXX_
#define KDEINETLAYER_HXX_
#ifndef KDEBACKEND_HXX_
#include "kdebackend.hxx"
#endif
#ifndef _COM_SUN_STAR_UNO_XCOMPONENTCONTEXT_HPP_
#include <com/sun/star/uno/XComponentContext.hpp>
#endif
#ifndef _COM_SUN_STAR_CONFIGURATION_BACKEND_XLAYER_HPP_
#include <com/sun/star/configuration/backend/XLayer.hpp>
#endif
#ifndef _COM_SUN_STAR_CONFIGURATION_BACKEND_BACKENDACCESSEXCEPTION_HPP_
#include <com/sun/star/configuration/backend/BackendAccessException.hpp>
#endif
#ifndef _COM_SUN_STAR_CONFIGURATION_BACKEND_XLAYERCONTENTDESCIBER_HPP_
#include <com/sun/star/configuration/backend/XLayerContentDescriber.hpp>
#endif
#ifndef _COM_SUN_STAR_UTIL_XTIMESTAMPED_HPP_
#include <com/sun/star/util/XTimeStamped.hpp>
#endif
#ifndef _CPPUHELPER_IMPLBASE2_HXX_
#include <cppuhelper/implbase2.hxx>
#endif
#ifndef QSTRING_H
#include <qstring.h>
#endif
namespace css = com::sun::star ;
namespace uno = css::uno ;
namespace lang = css::lang ;
namespace backend = css::configuration::backend ;
namespace util = css::util ;
/**
Implementation of the XLayer interface for the KDE values mapped into
the org.openoffice.Inet configuration component.
*/
class KDEInetLayer : public cppu::WeakImplHelper2<backend::XLayer, util::XTimeStamped>
{
public :
/**
Constructor given the component context
@param xContext The component context
*/
KDEInetLayer(const uno::Reference<uno::XComponentContext>& xContext);
// XLayer
virtual void SAL_CALL readData(
const uno::Reference<backend::XLayerHandler>& xHandler)
throw ( backend::MalformedDataException,
lang::NullPointerException,
lang::WrappedTargetException,
uno::RuntimeException) ;
// XTimeStamped
virtual rtl::OUString SAL_CALL getTimestamp(void)
throw (uno::RuntimeException);
protected:
/** Destructor */
~KDEInetLayer(void) {}
private :
uno::Reference<backend::XLayerContentDescriber> m_xLayerContentDescriber ;
void SAL_CALL setProxy
(uno::Sequence<backend::PropertyInfo> &aPropInfoList, sal_Int32 &nProperties,
int nProxyType, const QString &aNoProxyfor = QString(),
const QString &aHTTPProxy = QString(), const QString &aFTPProxy = QString()) const;
} ;
#endif // KDEINETLAYER
<commit_msg>INTEGRATION: CWS warningfixes01 (1.2.10); FILE MERGED 2006/06/27 13:57:30 sb 1.2.10.1: #i66722# Suppress warnings from external qstring.h.<commit_after>#ifndef KDEINETLAYER_HXX_
#define KDEINETLAYER_HXX_
#ifndef KDEBACKEND_HXX_
#include "kdebackend.hxx"
#endif
#ifndef _COM_SUN_STAR_UNO_XCOMPONENTCONTEXT_HPP_
#include <com/sun/star/uno/XComponentContext.hpp>
#endif
#ifndef _COM_SUN_STAR_CONFIGURATION_BACKEND_XLAYER_HPP_
#include <com/sun/star/configuration/backend/XLayer.hpp>
#endif
#ifndef _COM_SUN_STAR_CONFIGURATION_BACKEND_BACKENDACCESSEXCEPTION_HPP_
#include <com/sun/star/configuration/backend/BackendAccessException.hpp>
#endif
#ifndef _COM_SUN_STAR_CONFIGURATION_BACKEND_XLAYERCONTENTDESCIBER_HPP_
#include <com/sun/star/configuration/backend/XLayerContentDescriber.hpp>
#endif
#ifndef _COM_SUN_STAR_UTIL_XTIMESTAMPED_HPP_
#include <com/sun/star/util/XTimeStamped.hpp>
#endif
#ifndef _CPPUHELPER_IMPLBASE2_HXX_
#include <cppuhelper/implbase2.hxx>
#endif
#include "qstring_wrapper.h"
namespace css = com::sun::star ;
namespace uno = css::uno ;
namespace lang = css::lang ;
namespace backend = css::configuration::backend ;
namespace util = css::util ;
/**
Implementation of the XLayer interface for the KDE values mapped into
the org.openoffice.Inet configuration component.
*/
class KDEInetLayer : public cppu::WeakImplHelper2<backend::XLayer, util::XTimeStamped>
{
public :
/**
Constructor given the component context
@param xContext The component context
*/
KDEInetLayer(const uno::Reference<uno::XComponentContext>& xContext);
// XLayer
virtual void SAL_CALL readData(
const uno::Reference<backend::XLayerHandler>& xHandler)
throw ( backend::MalformedDataException,
lang::NullPointerException,
lang::WrappedTargetException,
uno::RuntimeException) ;
// XTimeStamped
virtual rtl::OUString SAL_CALL getTimestamp(void)
throw (uno::RuntimeException);
protected:
/** Destructor */
~KDEInetLayer(void) {}
private :
uno::Reference<backend::XLayerContentDescriber> m_xLayerContentDescriber ;
void SAL_CALL setProxy
(uno::Sequence<backend::PropertyInfo> &aPropInfoList, sal_Int32 &nProperties,
int nProxyType, const QString &aNoProxyfor = QString(),
const QString &aHTTPProxy = QString(), const QString &aFTPProxy = QString()) const;
} ;
#endif // KDEINETLAYER
<|endoftext|> |
<commit_before>#define NULL ((void*)0)
typedef unsigned long size_t;
namespace std {
enum class align_val_t : size_t {};
}
class exception {};
void cleanFunction();
void* operator new(size_t, float);
void* operator new[](size_t, float);
void* operator new(size_t, std::align_val_t, float);
void* operator new[](size_t, std::align_val_t, float);
void operator delete(void*, float);
void operator delete[](void*, float);
void operator delete(void*, std::align_val_t, float);
void operator delete[](void*, std::align_val_t, float);
struct myData
{
int sizeInt;
char* buffer;
};
struct myGlobalData
{
int sizeInt;
myData** bufMyData;
};
void allocData(myData ** bufMyData) {
for (size_t i = 0; i < 10; i++)
{
bufMyData[i] = new myData;
bufMyData[i]->sizeInt = 10;
bufMyData[i]->buffer = new char[10];
}
}
void throwFunction(int a) {
if (a == 5) throw "my exception!";
}
void throwFunction2(int a) {
if (a == 5) throw exception();
}
void funcWork1b() {
int a;
myData **bufMyData;
try {
cleanFunction();
throwFunction(a);
bufMyData = new myData*[10];
cleanFunction();
allocData(bufMyData);
cleanFunction();
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
delete[] bufMyData[i]->buffer; // BAD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork1() {
int a;
int i;
myData **bufMyData;
bufMyData = new myData*[10];
for (i = 0; i < 10; i++)
bufMyData[i] = 0;
try {
cleanFunction();
throwFunction(a);
cleanFunction();
allocData(bufMyData);
cleanFunction();
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
if (bufMyData[i])
delete[] bufMyData[i]->buffer; // GOOD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork2() {
int a;
myData **bufMyData;
bufMyData = new myData*[10];
try {
do {
cleanFunction();
allocData(bufMyData);
cleanFunction();
throwFunction(a);
}
while(0);
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
delete[] bufMyData[i]->buffer; // GOOD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork3() {
int a;
myData **bufMyData;
bufMyData = new myData*[10];
try {
cleanFunction();
allocData(bufMyData);
cleanFunction();
throwFunction(a);
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
delete[] bufMyData[i]->buffer; // GOOD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork4() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
delete valData;
valData = 0;
throwFunction(a);
}
catch (...)
{
delete valData; // GOOD
}
}
void funcWork4b() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
delete valData;
throwFunction(a);
}
catch (...)
{
delete valData; // BAD
}
}
void funcWork5() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
delete valData;
valData = 0;
throwFunction2(a);
}
catch (const exception &) {
delete valData;
valData = 0;
throw;
}
catch (...)
{
delete valData; // GOOD
}
}
void funcWork5b() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
throwFunction2(a);
}
catch (const exception &) {
delete valData;
throw;
}
catch (...)
{
delete valData; // BAD
}
}
void funcWork6() {
int a;
int flagB = 0;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
throwFunction2(a);
}
catch (const exception &) {
delete valData;
flagB = 1;
throw;
}
catch (...)
{
if(flagB == 0)
delete valData; // GOOD
}
}
void runnerFunc()
{
funcWork1();
funcWork1b();
funcWork2();
funcWork3();
funcWork4();
funcWork4b();
funcWork5();
funcWork5b();
funcWork6();
}
<commit_msg>Update test.cpp<commit_after>#define NULL ((void*)0)
typedef unsigned long size_t;
namespace std {
enum class align_val_t : size_t {};
}
class exception {};
void cleanFunction();
void* operator new(size_t, float);
void* operator new[](size_t, float);
void* operator new(size_t, std::align_val_t, float);
void* operator new[](size_t, std::align_val_t, float);
void operator delete(void*, float);
void operator delete[](void*, float);
void operator delete(void*, std::align_val_t, float);
void operator delete[](void*, std::align_val_t, float);
struct myData
{
int sizeInt;
char* buffer;
};
struct myGlobalData
{
int sizeInt;
myData** bufMyData;
};
void allocData(myData ** bufMyData) {
for (size_t i = 0; i < 10; i++)
{
bufMyData[i] = new myData;
bufMyData[i]->sizeInt = 10;
bufMyData[i]->buffer = new char[10];
}
}
void throwFunction(int a) {
if (a == 5) throw "my exception!";
}
void throwFunction2(int a) {
if (a == 5) throw exception();
}
void funcWork1b() {
int a;
myData **bufMyData;
try {
cleanFunction();
throwFunction(a);
bufMyData = new myData*[10];
cleanFunction();
allocData(bufMyData);
cleanFunction();
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
delete[] bufMyData[i]->buffer; // BAD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork1() {
int a;
int i;
myData **bufMyData;
bufMyData = new myData*[10];
for (i = 0; i < 10; i++)
bufMyData[i] = 0;
try {
cleanFunction();
throwFunction(a);
cleanFunction();
allocData(bufMyData);
cleanFunction();
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
if (bufMyData[i])
delete[] bufMyData[i]->buffer; // BAD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork2() {
int a;
myData **bufMyData;
bufMyData = new myData*[10];
try {
do {
cleanFunction();
allocData(bufMyData);
cleanFunction();
throwFunction(a);
}
while(0);
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
delete[] bufMyData[i]->buffer; // BAD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork3() {
int a;
myData **bufMyData;
bufMyData = new myData*[10];
try {
cleanFunction();
allocData(bufMyData);
cleanFunction();
throwFunction(a);
}
catch (...)
{
for (size_t i = 0; i < 10; i++)
{
delete[] bufMyData[i]->buffer; // BAD
delete bufMyData[i];
}
delete [] bufMyData;
}
}
void funcWork4() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
delete valData;
valData = 0;
throwFunction(a);
}
catch (...)
{
delete valData; // GOOD
}
}
void funcWork4b() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
delete valData;
throwFunction(a);
}
catch (...)
{
delete valData; // BAD
}
}
void funcWork5() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
delete valData;
valData = 0;
throwFunction2(a);
}
catch (const exception &) {
delete valData;
valData = 0;
throw;
}
catch (...)
{
delete valData; // GOOD
}
}
void funcWork5b() {
int a;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
throwFunction2(a);
}
catch (const exception &) {
delete valData;
throw;
}
catch (...)
{
delete valData; // BAD
}
}
void funcWork6() {
int a;
int flagB = 0;
myGlobalData *valData = 0;
try {
valData = new myGlobalData;
cleanFunction();
throwFunction2(a);
}
catch (const exception &) {
delete valData;
flagB = 1;
throw;
}
catch (...)
{
if(flagB == 0)
delete valData; // GOOD
}
}
void runnerFunc()
{
funcWork1();
funcWork1b();
funcWork2();
funcWork3();
funcWork4();
funcWork4b();
funcWork5();
funcWork5b();
funcWork6();
}
<|endoftext|> |
<commit_before>#include "perf_precomp.hpp"
using namespace std;
using namespace cv;
using namespace perf;
using std::tr1::make_tuple;
using std::tr1::get;
typedef std::tr1::tuple<Size, MatType, MatType, int, double> Size_DepthSrc_DepthDst_Channels_alpha_t;
typedef perf::TestBaseWithParam<Size_DepthSrc_DepthDst_Channels_alpha_t> Size_DepthSrc_DepthDst_Channels_alpha;
PERF_TEST_P( Size_DepthSrc_DepthDst_Channels_alpha, convertTo,
testing::Combine
(
testing::Values(szVGA, sz1080p),
testing::Values(CV_8U, CV_8S, CV_16U, CV_16S, CV_32S, CV_32F, CV_64F),
testing::Values(CV_8U, CV_8S, CV_16U, CV_16S, CV_32S, CV_32F, CV_64F),
testing::Values(1, 4),
testing::Values(1.0, 1./255)
)
)
{
Size sz = get<0>(GetParam());
int depthSrc = get<1>(GetParam());
int depthDst = get<2>(GetParam());
int channels = get<3>(GetParam());
double alpha = get<4>(GetParam());
Mat src(sz, CV_MAKETYPE(depthSrc, channels));
randu(src, 0, 255);
Mat dst(sz, CV_MAKETYPE(depthDst, channels));
TEST_CYCLE() src.convertTo(dst, depthDst, alpha);
SANITY_CHECK(dst, 1e-12);
}
<commit_msg>Updated sanity threshold for convertTo perf test<commit_after>#include "perf_precomp.hpp"
using namespace std;
using namespace cv;
using namespace perf;
using std::tr1::make_tuple;
using std::tr1::get;
typedef std::tr1::tuple<Size, MatType, MatType, int, double> Size_DepthSrc_DepthDst_Channels_alpha_t;
typedef perf::TestBaseWithParam<Size_DepthSrc_DepthDst_Channels_alpha_t> Size_DepthSrc_DepthDst_Channels_alpha;
PERF_TEST_P( Size_DepthSrc_DepthDst_Channels_alpha, convertTo,
testing::Combine
(
testing::Values(szVGA, sz1080p),
testing::Values(CV_8U, CV_8S, CV_16U, CV_16S, CV_32S, CV_32F, CV_64F),
testing::Values(CV_8U, CV_8S, CV_16U, CV_16S, CV_32S, CV_32F, CV_64F),
testing::Values(1, 4),
testing::Values(1.0, 1./255)
)
)
{
Size sz = get<0>(GetParam());
int depthSrc = get<1>(GetParam());
int depthDst = get<2>(GetParam());
int channels = get<3>(GetParam());
double alpha = get<4>(GetParam());
Mat src(sz, CV_MAKETYPE(depthSrc, channels));
randu(src, 0, 255);
Mat dst(sz, CV_MAKETYPE(depthDst, channels));
TEST_CYCLE() src.convertTo(dst, depthDst, alpha);
SANITY_CHECK(dst, alpha == 1.0 ? 1e-12 : 1e-7);
}
<|endoftext|> |
<commit_before>/*************************************************************************
*
* $RCSfile: breakiterator_cjk.cxx,v $
*
* $Revision: 1.7 $
*
* last change: $Author: khong $ $Date: 2002-12-05 19:12:14 $
*
* The Contents of this file are made available subject to the terms of
* either of the following licenses
*
* - GNU Lesser General Public License Version 2.1
* - Sun Industry Standards Source License Version 1.1
*
* Sun Microsystems Inc., October, 2000
*
* GNU Lesser General Public License Version 2.1
* =============================================
* Copyright 2000 by Sun Microsystems, Inc.
* 901 San Antonio Road, Palo Alto, CA 94303, USA
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License version 2.1, as published by the Free Software Foundation.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307 USA
*
*
* Sun Industry Standards Source License Version 1.1
* =================================================
* The contents of this file are subject to the Sun Industry Standards
* Source License Version 1.1 (the "License"); You may not use this file
* except in compliance with the License. You may obtain a copy of the
* License at http://www.openoffice.org/license.html.
*
* Software provided under this License is provided on an "AS IS" basis,
* WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING,
* WITHOUT LIMITATION, WARRANTIES THAT THE SOFTWARE IS FREE OF DEFECTS,
* MERCHANTABLE, FIT FOR A PARTICULAR PURPOSE, OR NON-INFRINGING.
* See the License for the specific provisions governing your rights and
* obligations concerning the Software.
*
* The Initial Developer of the Original Code is: Sun Microsystems, Inc.
*
* Copyright: 2000 by Sun Microsystems, Inc.
*
* All Rights Reserved.
*
* Contributor(s): _______________________________________
*
*
************************************************************************/
#define BREAKITERATOR_ALL
#include <breakiterator_cjk.hxx>
#include <unicode.hxx>
using namespace ::com::sun::star::uno;
using namespace ::com::sun::star::lang;
using namespace ::rtl;
namespace com { namespace sun { namespace star { namespace i18n {
// ----------------------------------------------------
// class BreakIterator_CJK
// ----------------------------------------------------;
BreakIterator_CJK::BreakIterator_CJK() : dict(NULL)
{
cBreakIterator = "com.sun.star.i18n.BreakIterator_CJK";
}
Boundary SAL_CALL
BreakIterator_CJK::previousWord(const OUString& text, sal_Int32 anyPos,
const lang::Locale& nLocale, sal_Int16 wordType) throw(RuntimeException)
{
if (dict)
return dict->previousWord(text.getStr(), anyPos, text.getLength(), wordType);
else
return BreakIterator_Unicode::previousWord(text, anyPos, nLocale, wordType);
}
Boundary SAL_CALL
BreakIterator_CJK::nextWord(const OUString& text, sal_Int32 anyPos,
const lang::Locale& nLocale, sal_Int16 wordType) throw(RuntimeException)
{
if (dict)
return dict->nextWord(text.getStr(), anyPos, text.getLength(), wordType);
else
return BreakIterator_Unicode::nextWord(text, anyPos, nLocale, wordType);
}
Boundary SAL_CALL
BreakIterator_CJK::getWordBoundary( const OUString& text, sal_Int32 anyPos,
const lang::Locale& nLocale, sal_Int16 wordType, sal_Bool bDirection )
throw(RuntimeException)
{
if (dict)
return dict->getWordBoundary(text.getStr(), anyPos, text.getLength(), wordType, bDirection);
else
return BreakIterator_Unicode::getWordBoundary(text, anyPos, nLocale, wordType, bDirection);
}
LineBreakResults SAL_CALL BreakIterator_CJK::getLineBreak(
const OUString& Text, sal_Int32 nStartPos,
const lang::Locale& rLocale, sal_Int32 nMinBreakPos,
const LineBreakHyphenationOptions& hOptions,
const LineBreakUserOptions& bOptions ) throw(RuntimeException)
{
LineBreakResults result;
if (bOptions.allowPunctuationOutsideMargin &&
bOptions.forbiddenBeginCharacters.indexOf(Text[nStartPos]) != -1 &&
++nStartPos == Text.getLength()) {
; // do nothing
} else if (bOptions.applyForbiddenRules && 0 < nStartPos && nStartPos < Text.getLength()) {
while (nStartPos > 0 &&
(bOptions.forbiddenBeginCharacters.indexOf(Text[nStartPos]) != -1 ||
bOptions.forbiddenEndCharacters.indexOf(Text[nStartPos-1]) != -1))
nStartPos--;
}
result.breakIndex = nStartPos;
result.breakType = BreakType::WORDBOUNDARY;
return result;
}
// ----------------------------------------------------
// class BreakIterator_zh
// ----------------------------------------------------;
BreakIterator_zh::BreakIterator_zh()
{
dict = new xdictionary("zh");
cBreakIterator = "com.sun.star.i18n.BreakIterator_zh";
}
BreakIterator_zh::~BreakIterator_zh()
{
delete dict;
}
// ----------------------------------------------------
// class BreakIterator_ja
// ----------------------------------------------------;
BreakIterator_ja::BreakIterator_ja()
{
dict = new xdictionary("ja");
cBreakIterator = "com.sun.star.i18n.BreakIterator_ja";
}
BreakIterator_ja::~BreakIterator_ja()
{
delete dict;
}
// ----------------------------------------------------
// class BreakIterator_ko
// ----------------------------------------------------;
BreakIterator_ko::BreakIterator_ko()
{
cBreakIterator = "com.sun.star.i18n.BreakIterator_ko";
}
BreakIterator_ko::~BreakIterator_ko()
{
}
} } } }
<commit_msg>INTEGRATION: CWS i18napi (1.7.46); FILE MERGED 2003/04/19 19:40:58 er 1.7.46.1: #107686# drafts.com.sun.star.i18n to com.sun.star.i18n<commit_after>/*************************************************************************
*
* $RCSfile: breakiterator_cjk.cxx,v $
*
* $Revision: 1.8 $
*
* last change: $Author: vg $ $Date: 2003-04-24 11:05:16 $
*
* The Contents of this file are made available subject to the terms of
* either of the following licenses
*
* - GNU Lesser General Public License Version 2.1
* - Sun Industry Standards Source License Version 1.1
*
* Sun Microsystems Inc., October, 2000
*
* GNU Lesser General Public License Version 2.1
* =============================================
* Copyright 2000 by Sun Microsystems, Inc.
* 901 San Antonio Road, Palo Alto, CA 94303, USA
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License version 2.1, as published by the Free Software Foundation.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston,
* MA 02111-1307 USA
*
*
* Sun Industry Standards Source License Version 1.1
* =================================================
* The contents of this file are subject to the Sun Industry Standards
* Source License Version 1.1 (the "License"); You may not use this file
* except in compliance with the License. You may obtain a copy of the
* License at http://www.openoffice.org/license.html.
*
* Software provided under this License is provided on an "AS IS" basis,
* WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING,
* WITHOUT LIMITATION, WARRANTIES THAT THE SOFTWARE IS FREE OF DEFECTS,
* MERCHANTABLE, FIT FOR A PARTICULAR PURPOSE, OR NON-INFRINGING.
* See the License for the specific provisions governing your rights and
* obligations concerning the Software.
*
* The Initial Developer of the Original Code is: Sun Microsystems, Inc.
*
* Copyright: 2000 by Sun Microsystems, Inc.
*
* All Rights Reserved.
*
* Contributor(s): _______________________________________
*
*
************************************************************************/
#define BREAKITERATOR_ALL
#include <breakiterator_cjk.hxx>
#include <i18nutil/unicode.hxx>
using namespace ::com::sun::star::uno;
using namespace ::com::sun::star::lang;
using namespace ::rtl;
namespace com { namespace sun { namespace star { namespace i18n {
// ----------------------------------------------------
// class BreakIterator_CJK
// ----------------------------------------------------;
BreakIterator_CJK::BreakIterator_CJK() : dict(NULL)
{
cBreakIterator = "com.sun.star.i18n.BreakIterator_CJK";
}
Boundary SAL_CALL
BreakIterator_CJK::previousWord(const OUString& text, sal_Int32 anyPos,
const lang::Locale& nLocale, sal_Int16 wordType) throw(RuntimeException)
{
if (dict)
return dict->previousWord(text.getStr(), anyPos, text.getLength(), wordType);
else
return BreakIterator_Unicode::previousWord(text, anyPos, nLocale, wordType);
}
Boundary SAL_CALL
BreakIterator_CJK::nextWord(const OUString& text, sal_Int32 anyPos,
const lang::Locale& nLocale, sal_Int16 wordType) throw(RuntimeException)
{
if (dict)
return dict->nextWord(text.getStr(), anyPos, text.getLength(), wordType);
else
return BreakIterator_Unicode::nextWord(text, anyPos, nLocale, wordType);
}
Boundary SAL_CALL
BreakIterator_CJK::getWordBoundary( const OUString& text, sal_Int32 anyPos,
const lang::Locale& nLocale, sal_Int16 wordType, sal_Bool bDirection )
throw(RuntimeException)
{
if (dict)
return dict->getWordBoundary(text.getStr(), anyPos, text.getLength(), wordType, bDirection);
else
return BreakIterator_Unicode::getWordBoundary(text, anyPos, nLocale, wordType, bDirection);
}
LineBreakResults SAL_CALL BreakIterator_CJK::getLineBreak(
const OUString& Text, sal_Int32 nStartPos,
const lang::Locale& rLocale, sal_Int32 nMinBreakPos,
const LineBreakHyphenationOptions& hOptions,
const LineBreakUserOptions& bOptions ) throw(RuntimeException)
{
LineBreakResults result;
if (bOptions.allowPunctuationOutsideMargin &&
bOptions.forbiddenBeginCharacters.indexOf(Text[nStartPos]) != -1 &&
++nStartPos == Text.getLength()) {
; // do nothing
} else if (bOptions.applyForbiddenRules && 0 < nStartPos && nStartPos < Text.getLength()) {
while (nStartPos > 0 &&
(bOptions.forbiddenBeginCharacters.indexOf(Text[nStartPos]) != -1 ||
bOptions.forbiddenEndCharacters.indexOf(Text[nStartPos-1]) != -1))
nStartPos--;
}
result.breakIndex = nStartPos;
result.breakType = BreakType::WORDBOUNDARY;
return result;
}
// ----------------------------------------------------
// class BreakIterator_zh
// ----------------------------------------------------;
BreakIterator_zh::BreakIterator_zh()
{
dict = new xdictionary("zh");
cBreakIterator = "com.sun.star.i18n.BreakIterator_zh";
}
BreakIterator_zh::~BreakIterator_zh()
{
delete dict;
}
// ----------------------------------------------------
// class BreakIterator_ja
// ----------------------------------------------------;
BreakIterator_ja::BreakIterator_ja()
{
dict = new xdictionary("ja");
cBreakIterator = "com.sun.star.i18n.BreakIterator_ja";
}
BreakIterator_ja::~BreakIterator_ja()
{
delete dict;
}
// ----------------------------------------------------
// class BreakIterator_ko
// ----------------------------------------------------;
BreakIterator_ko::BreakIterator_ko()
{
cBreakIterator = "com.sun.star.i18n.BreakIterator_ko";
}
BreakIterator_ko::~BreakIterator_ko()
{
}
} } } }
<|endoftext|> |
<commit_before>/*
* Copyright © 2010 Intel Corporation
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice (including the next
* paragraph) shall be included in all copies or substantial portions of the
* Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#include <stdio.h>
#include "glsl_parser_extras.h"
/* A dummy file. When compiling prototypes, we don't care about builtins.
* We really don't want to half-compile builtin_functions.cpp and fail, though.
*/
void
_mesa_glsl_release_functions(void)
{
}
void
_mesa_glsl_initialize_functions(exec_list *instructions,
struct _mesa_glsl_parse_state *state)
{
}
<commit_msg>glsl: Really remove unused "instructions" parameter.<commit_after>/*
* Copyright © 2010 Intel Corporation
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice (including the next
* paragraph) shall be included in all copies or substantial portions of the
* Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*/
#include <stdio.h>
#include "glsl_parser_extras.h"
/* A dummy file. When compiling prototypes, we don't care about builtins.
* We really don't want to half-compile builtin_functions.cpp and fail, though.
*/
void
_mesa_glsl_release_functions(void)
{
}
void
_mesa_glsl_initialize_functions(_mesa_glsl_parse_state *state)
{
}
<|endoftext|> |
<commit_before>/*****************************************************************************
*
* This file is part of Mapnik (c++ mapping toolkit)
*
* Copyright (C) 2017 Artem Pavlenko
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
*****************************************************************************/
#ifndef MAPNIK_SVG_TRANSFORM_GRAMMAR_X3_DEF_HPP
#define MAPNIK_SVG_TRANSFORM_GRAMMAR_X3_DEF_HPP
// mapnik
#include <mapnik/svg/svg_transform_grammar_x3.hpp>
// boost::fusion
#pragma GCC diagnostic push
#include <mapnik/warning_ignore.hpp>
#include <boost/fusion/sequence.hpp>
#pragma GCC diagnostic pop
// agg
#pragma GCC diagnostic push
#include <mapnik/warning_ignore_agg.hpp>
#include <agg_trans_affine.h>
#pragma GCC diagnostic pop
namespace mapnik { namespace svg { namespace grammar {
namespace x3 = boost::spirit::x3;
using x3::lit;
using x3::double_;
using x3::no_case;
auto const matrix_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto a = boost::fusion::at_c<0>(attr);
auto b = boost::fusion::at_c<1>(attr);
auto c = boost::fusion::at_c<2>(attr);
auto d = boost::fusion::at_c<3>(attr);
auto e = boost::fusion::at_c<4>(attr);
auto f = boost::fusion::at_c<5>(attr);
tr = agg::trans_affine(a, b, c, d, e, f) * tr;
};
auto const rotate_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto a = boost::fusion::at_c<0>(attr);
auto cx = boost::fusion::at_c<1>(attr) ? *boost::fusion::at_c<1>(attr) : 0.0;
auto cy = boost::fusion::at_c<2>(attr) ? *boost::fusion::at_c<2>(attr) : 0.0;
if (cx == 0.0 && cy == 0.0)
{
tr = agg::trans_affine_rotation(deg2rad(a)) * tr;
}
else
{
agg::trans_affine t = agg::trans_affine_translation(-cx,-cy);
t *= agg::trans_affine_rotation(deg2rad(a));
t *= agg::trans_affine_translation(cx, cy);
tr = t * tr;
}
};
auto const translate_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto tx = boost::fusion::at_c<0>(attr);
auto ty = boost::fusion::at_c<1>(attr);
if (ty) tr = agg::trans_affine_translation(tx, *ty) * tr;
else tr = agg::trans_affine_translation(tx,0.0) * tr;
};
auto const scale_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto sx = boost::fusion::at_c<0>(attr);
auto sy = boost::fusion::at_c<1>(attr);
if (sy) tr = agg::trans_affine_scaling(sx, *sy) * tr;
else tr = agg::trans_affine_scaling(sx, sx) * tr;
};
auto const skewX_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto skew_x = _attr(ctx);
tr = agg::trans_affine_skewing(deg2rad(skew_x), 0.0) * tr;
};
auto const skewY_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto skew_y= _attr(ctx);
tr = agg::trans_affine_skewing(0.0, deg2rad(skew_y)) * tr;
};
//exported rule
svg_transform_grammar_type const svg_transform = "SVG Transform";
// rules
auto const matrix = x3::rule<class matrix_tag> {} = no_case[lit("matrix")]
> lit('(') > (double_ > -lit(',')
> double_ > -lit(',')
> double_ > -lit(',')
> double_ > -lit(',')
> double_ > -lit(',')
> double_)[matrix_action]
> lit(')');
auto const translate = x3::rule<class translate_tag> {} = no_case[lit("translate")]
> lit('(') > (double_ > -lit(',') >> -double_)[translate_action] > lit(')');
auto const scale = x3::rule<class scale_tag> {} = no_case[lit("scale")]
> lit('(') > (double_ > -lit(',') > -double_)[scale_action] > lit(')');
auto const rotate = x3::rule<class rotate_tag> {} = no_case[lit("rotate")]
> lit('(')
> (double_ > -(lit(',') > double_) > -(lit(',') > double_))[rotate_action]
> lit(')') ;
auto const skewX = x3::rule<class skewX_tag> {} = no_case[lit("skewX")]
> lit('(') > double_ [ skewX_action] > lit(')');
auto const skewY = x3::rule<class skewY_tag> {} = no_case[lit("skewY")]
> lit('(') > double_ [ skewY_action] > lit(')');
auto const transform = x3::rule<class transform_tag> {} = matrix | rotate | translate | scale /*| rotate*/ | skewX | skewY ;
auto const svg_transform_def = +transform ;
#pragma GCC diagnostic push
#include <mapnik/warning_ignore.hpp>
BOOST_SPIRIT_DEFINE(
svg_transform
);
#pragma GCC diagnostic pop
}
grammar::svg_transform_grammar_type const& svg_transform_grammar()
{
return grammar::svg_transform;
}
}}
#endif // MAPNIK_SVG_TRANSFORM_GRAMMAR_X3_HPP
<commit_msg>svg transform - correct `rotate(<a> [<x> <y>])` rule (ref #763)<commit_after>/*****************************************************************************
*
* This file is part of Mapnik (c++ mapping toolkit)
*
* Copyright (C) 2017 Artem Pavlenko
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
*****************************************************************************/
#ifndef MAPNIK_SVG_TRANSFORM_GRAMMAR_X3_DEF_HPP
#define MAPNIK_SVG_TRANSFORM_GRAMMAR_X3_DEF_HPP
// mapnik
#include <mapnik/svg/svg_transform_grammar_x3.hpp>
// boost::fusion
#pragma GCC diagnostic push
#include <mapnik/warning_ignore.hpp>
#include <boost/fusion/sequence.hpp>
#pragma GCC diagnostic pop
// agg
#pragma GCC diagnostic push
#include <mapnik/warning_ignore_agg.hpp>
#include <agg_trans_affine.h>
#pragma GCC diagnostic pop
namespace mapnik { namespace svg { namespace grammar {
namespace x3 = boost::spirit::x3;
using x3::lit;
using x3::double_;
using x3::no_case;
auto const matrix_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto a = boost::fusion::at_c<0>(attr);
auto b = boost::fusion::at_c<1>(attr);
auto c = boost::fusion::at_c<2>(attr);
auto d = boost::fusion::at_c<3>(attr);
auto e = boost::fusion::at_c<4>(attr);
auto f = boost::fusion::at_c<5>(attr);
tr = agg::trans_affine(a, b, c, d, e, f) * tr;
};
auto const rotate_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto a = boost::fusion::at_c<0>(attr);
auto cx = boost::fusion::at_c<1>(attr) ? *boost::fusion::at_c<1>(attr) : 0.0;
auto cy = boost::fusion::at_c<2>(attr) ? *boost::fusion::at_c<2>(attr) : 0.0;
if (cx == 0.0 && cy == 0.0)
{
tr = agg::trans_affine_rotation(deg2rad(a)) * tr;
}
else
{
agg::trans_affine t = agg::trans_affine_translation(-cx, -cy);
t *= agg::trans_affine_rotation(deg2rad(a));
t *= agg::trans_affine_translation(cx, cy);
tr = t * tr;
}
};
auto const translate_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto tx = boost::fusion::at_c<0>(attr);
auto ty = boost::fusion::at_c<1>(attr);
if (ty) tr = agg::trans_affine_translation(tx, *ty) * tr;
else tr = agg::trans_affine_translation(tx,0.0) * tr;
};
auto const scale_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto const& attr = _attr(ctx);
auto sx = boost::fusion::at_c<0>(attr);
auto sy = boost::fusion::at_c<1>(attr);
if (sy) tr = agg::trans_affine_scaling(sx, *sy) * tr;
else tr = agg::trans_affine_scaling(sx, sx) * tr;
};
auto const skewX_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto skew_x = _attr(ctx);
tr = agg::trans_affine_skewing(deg2rad(skew_x), 0.0) * tr;
};
auto const skewY_action = [] (auto const& ctx)
{
auto & tr = x3::get<svg_transform_tag>(ctx).get();
auto skew_y= _attr(ctx);
tr = agg::trans_affine_skewing(0.0, deg2rad(skew_y)) * tr;
};
//exported rule
svg_transform_grammar_type const svg_transform = "SVG Transform";
// rules
auto const matrix = x3::rule<class matrix_tag> {} = no_case[lit("matrix")]
> lit('(') > (double_ > -lit(',')
> double_ > -lit(',')
> double_ > -lit(',')
> double_ > -lit(',')
> double_ > -lit(',')
> double_)[matrix_action]
> lit(')');
auto const translate = x3::rule<class translate_tag> {} = no_case[lit("translate")]
> lit('(') > (double_ > -lit(',') >> -double_)[translate_action] > lit(')');
auto const scale = x3::rule<class scale_tag> {} = no_case[lit("scale")]
> lit('(') > (double_ > -lit(',') > -double_)[scale_action] > lit(')');
auto const rotate = x3::rule<class rotate_tag> {} = no_case[lit("rotate")]
> lit('(')
> (double_ > -lit(',') > -double_ > -lit(',') > -double_)[rotate_action]
> lit(')') ;
auto const skewX = x3::rule<class skewX_tag> {} = no_case[lit("skewX")]
> lit('(') > double_ [ skewX_action] > lit(')');
auto const skewY = x3::rule<class skewY_tag> {} = no_case[lit("skewY")]
> lit('(') > double_ [ skewY_action] > lit(')');
auto const transform = x3::rule<class transform_tag> {} = matrix | rotate | translate | scale /*| rotate*/ | skewX | skewY ;
auto const svg_transform_def = +transform ;
#pragma GCC diagnostic push
#include <mapnik/warning_ignore.hpp>
BOOST_SPIRIT_DEFINE(
svg_transform
);
#pragma GCC diagnostic pop
}
grammar::svg_transform_grammar_type const& svg_transform_grammar()
{
return grammar::svg_transform;
}
}}
#endif // MAPNIK_SVG_TRANSFORM_GRAMMAR_X3_HPP
<|endoftext|> |
<commit_before>/* -*- Mode: C++; tab-width: 4; indent-tabs-mode: nil; c-basic-offset: 4 -*- */
/*
* This file is part of the LibreOffice project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* This file incorporates work covered by the following license notice:
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed
* with this work for additional information regarding copyright
* ownership. The ASF licenses this file to you under the Apache
* License, Version 2.0 (the "License"); you may not use this file
* except in compliance with the License. You may obtain a copy of
* the License at http://www.apache.org/licenses/LICENSE-2.0 .
*/
#include "cuihyperdlg.hxx"
#include <unotools/localfilehelper.hxx>
#include <sfx2/filedlghelper.hxx>
#include "com/sun/star/ui/dialogs/TemplateDescription.hpp"
#include "hldoctp.hxx"
#include "hyperdlg.hrc"
#include "hlmarkwn_def.hxx"
sal_Char const sHash[] = "#";
sal_Char const sFileScheme[] = INET_FILE_SCHEME;
/*************************************************************************
|*
|* Contructor / Destructor
|*
|************************************************************************/
SvxHyperlinkDocTp::SvxHyperlinkDocTp ( Window *pParent, const SfxItemSet& rItemSet)
: SvxHyperlinkTabPageBase ( pParent, CUI_RES( RID_SVXPAGE_HYPERLINK_DOCUMENT ), rItemSet ),
maGrpDocument ( this, CUI_RES (GRP_DOCUMENT) ),
maFtPath ( this, CUI_RES (FT_PATH_DOC) ),
maCbbPath ( this, INET_PROT_FILE ),
maBtFileopen ( this, CUI_RES (BTN_FILEOPEN) ),
maGrpTarget ( this, CUI_RES (GRP_TARGET) ),
maFtTarget ( this, CUI_RES (FT_TARGET_DOC) ),
maEdTarget ( this, CUI_RES (ED_TARGET_DOC) ),
maFtURL ( this, CUI_RES (FT_URL) ),
maFtFullURL ( this, CUI_RES (FT_FULL_URL) ),
maBtBrowse ( this, CUI_RES (BTN_BROWSE) ),
mbMarkWndOpen ( sal_False )
{
// Disable display of bitmap names.
maBtBrowse.EnableTextDisplay (false);
maBtFileopen.EnableTextDisplay (false);
InitStdControls();
FreeResource();
// Init URL-Box (pos&size, Open-Handler)
maCbbPath.SetPosSizePixel ( LogicToPixel( Point( COL_2, 15 ), MAP_APPFONT ),
LogicToPixel( Size ( 176 - COL_DIFF, 60), MAP_APPFONT ) );
maCbbPath.Show();
OUString aFileScheme( INET_FILE_SCHEME );
maCbbPath.SetBaseURL(aFileScheme);
maCbbPath.SetHelpId( HID_HYPERDLG_DOC_PATH );
SetExchangeSupport ();
// overload handlers
maBtFileopen.SetClickHdl ( LINK ( this, SvxHyperlinkDocTp, ClickFileopenHdl_Impl ) );
maBtBrowse.SetClickHdl ( LINK ( this, SvxHyperlinkDocTp, ClickTargetHdl_Impl ) );
maCbbPath.SetModifyHdl ( LINK ( this, SvxHyperlinkDocTp, ModifiedPathHdl_Impl ) );
maEdTarget.SetModifyHdl ( LINK ( this, SvxHyperlinkDocTp, ModifiedTargetHdl_Impl ) );
maCbbPath.SetLoseFocusHdl( LINK ( this, SvxHyperlinkDocTp, LostFocusPathHdl_Impl ) );
maBtBrowse.SetAccessibleRelationMemberOf( &maGrpTarget );
maBtBrowse.SetAccessibleRelationLabeledBy( &maFtTarget );
maBtFileopen.SetAccessibleRelationMemberOf( &maGrpDocument );
maBtFileopen.SetAccessibleRelationLabeledBy( &maFtPath );
maTimer.SetTimeoutHdl ( LINK ( this, SvxHyperlinkDocTp, TimeoutHdl_Impl ) );
}
SvxHyperlinkDocTp::~SvxHyperlinkDocTp ()
{
}
/*************************************************************************
|*
|* Fill all dialog-controls except controls in groupbox "more..."
|*
|************************************************************************/
void SvxHyperlinkDocTp::FillDlgFields(const OUString& rStrURL)
{
sal_Int32 nPos = rStrURL.indexOf(sHash);
// path
maCbbPath.SetText ( rStrURL.copy( 0, ( nPos == -1 ? rStrURL.getLength() : nPos ) ) );
// set target in document at editfield
OUString aStrMark;
if ( nPos != -1 && nPos < rStrURL.getLength()-1 )
aStrMark = rStrURL.copy( nPos+1, rStrURL.getLength() );
maEdTarget.SetText ( aStrMark );
ModifiedPathHdl_Impl ( NULL );
}
/*************************************************************************
|*
|* retrieve current url-string
|*
|************************************************************************/
OUString SvxHyperlinkDocTp::GetCurrentURL ()
{
// get data from dialog-controls
OUString aStrURL;
OUString aStrPath ( maCbbPath.GetText() );
const OUString aBaseURL ( maCbbPath.GetBaseURL() );
OUString aStrMark( maEdTarget.GetText() );
if ( aStrPath != aEmptyStr )
{
INetURLObject aURL( aStrPath );
if ( aURL.GetProtocol() != INET_PROT_NOT_VALID ) // maybe the path is already a valid
aStrURL = aStrPath; // hyperlink, then we can use this path directly
else
utl::LocalFileHelper::ConvertSystemPathToURL( aStrPath, aBaseURL, aStrURL );
//#105788# always create a URL even if it is not valid
if( aStrURL == aEmptyStr )
aStrURL = aStrPath;
}
if( aStrMark != aEmptyStr )
{
aStrURL += OUString( sHash );
aStrURL += aStrMark;
}
return aStrURL;
}
/*************************************************************************
|*
|* retrieve and prepare data from dialog-fields
|*
|************************************************************************/
void SvxHyperlinkDocTp::GetCurentItemData ( OUString& rStrURL, OUString& aStrName,
OUString& aStrIntName, OUString& aStrFrame,
SvxLinkInsertMode& eMode )
{
// get data from standard-fields
rStrURL = GetCurrentURL();
if( rStrURL.equalsIgnoreAsciiCase( sFileScheme ) )
rStrURL = "";
GetDataFromCommonFields( aStrName, aStrIntName, aStrFrame, eMode );
}
/*************************************************************************
|*
|* static method to create Tabpage
|*
|************************************************************************/
IconChoicePage* SvxHyperlinkDocTp::Create( Window* pWindow, const SfxItemSet& rItemSet )
{
return( new SvxHyperlinkDocTp( pWindow, rItemSet ) );
}
/*************************************************************************
|*
|* Set initial focus
|*
|************************************************************************/
void SvxHyperlinkDocTp::SetInitFocus()
{
maCbbPath.GrabFocus();
}
/*************************************************************************
|*
|* Click on imagebutton : fileopen
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ClickFileopenHdl_Impl)
{
// Open Fileopen-Dialog
::sfx2::FileDialogHelper aDlg(
com::sun::star::ui::dialogs::TemplateDescription::FILEOPEN_SIMPLE, 0,
GetParent() );
OUString aOldURL( GetCurrentURL() );
if( aOldURL.startsWithIgnoreAsciiCase( sFileScheme ) )
{
aDlg.SetDisplayDirectory( aOldURL );
}
DisableClose( sal_True );
ErrCode nError = aDlg.Execute();
DisableClose( sal_False );
if ( ERRCODE_NONE == nError )
{
OUString aURL( aDlg.GetPath() );
OUString aPath;
utl::LocalFileHelper::ConvertURLToSystemPath( aURL, aPath );
maCbbPath.SetBaseURL( aURL );
maCbbPath.SetText( aPath );
if ( aOldURL != GetCurrentURL() )
ModifiedPathHdl_Impl (NULL);
}
return( 0L );
}
/*************************************************************************
|*
|* Click on imagebutton : target
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ClickTargetHdl_Impl)
{
if ( GetPathType ( maStrURL ) == Type_ExistsFile ||
maStrURL.isEmpty() ||
maStrURL.equalsIgnoreAsciiCase( sFileScheme ) ||
maStrURL.startsWith( sHash ) )
{
mpMarkWnd->SetError( LERR_NOERROR );
EnterWait();
if ( maStrURL.equalsIgnoreAsciiCase( sFileScheme ) )
mpMarkWnd->RefreshTree ( aEmptyStr );
else
mpMarkWnd->RefreshTree ( maStrURL );
LeaveWait();
}
else
mpMarkWnd->SetError( LERR_DOCNOTOPEN );
ShowMarkWnd ();
return( 0L );
}
/*************************************************************************
|*
|* Contens of combobox "Path" modified
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ModifiedPathHdl_Impl)
{
maStrURL = GetCurrentURL();
maTimer.SetTimeout( 2500 );
maTimer.Start();
maFtFullURL.SetText( maStrURL );
return( 0L );
}
/*************************************************************************
|*
|* If path-field was modify, to browse the new doc after timeout
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, TimeoutHdl_Impl)
{
if ( IsMarkWndVisible() && ( GetPathType( maStrURL )==Type_ExistsFile ||
maStrURL.isEmpty() ||
maStrURL.equalsIgnoreAsciiCase( sFileScheme ) ) )
{
EnterWait();
if ( maStrURL.equalsIgnoreAsciiCase( sFileScheme ) )
mpMarkWnd->RefreshTree ( aEmptyStr );
else
mpMarkWnd->RefreshTree ( maStrURL );
LeaveWait();
}
return( 0L );
}
/*************************************************************************
|*
|* Contens of editfield "Target" modified
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ModifiedTargetHdl_Impl)
{
maStrURL = GetCurrentURL();
if ( IsMarkWndVisible() )
mpMarkWnd->SelectEntry ( maEdTarget.GetText() );
maFtFullURL.SetText( maStrURL );
return( 0L );
}
/*************************************************************************
|*
|* editfield "Target" lost focus
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, LostFocusPathHdl_Impl)
{
maStrURL = GetCurrentURL();
maFtFullURL.SetText( maStrURL );
return (0L);
}
/*************************************************************************
|*
|* Get String from Bookmark-Wnd
|*
|************************************************************************/
void SvxHyperlinkDocTp::SetMarkStr ( const OUString& aStrMark )
{
maEdTarget.SetText ( aStrMark );
ModifiedTargetHdl_Impl ( NULL );
}
/*************************************************************************
|*
|* retrieve kind of pathstr
|*
|************************************************************************/
SvxHyperlinkDocTp::EPathType SvxHyperlinkDocTp::GetPathType ( const OUString& rStrPath )
{
INetURLObject aURL( rStrPath, INET_PROT_FILE );
if( aURL.HasError() )
return Type_Invalid;
else
return Type_ExistsFile;
}
/* vim:set shiftwidth=4 softtabstop=4 expandtab: */
<commit_msg>fdo#75968 Fix OUString conversion<commit_after>/* -*- Mode: C++; tab-width: 4; indent-tabs-mode: nil; c-basic-offset: 4 -*- */
/*
* This file is part of the LibreOffice project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* This file incorporates work covered by the following license notice:
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed
* with this work for additional information regarding copyright
* ownership. The ASF licenses this file to you under the Apache
* License, Version 2.0 (the "License"); you may not use this file
* except in compliance with the License. You may obtain a copy of
* the License at http://www.apache.org/licenses/LICENSE-2.0 .
*/
#include "cuihyperdlg.hxx"
#include <unotools/localfilehelper.hxx>
#include <sfx2/filedlghelper.hxx>
#include "com/sun/star/ui/dialogs/TemplateDescription.hpp"
#include "hldoctp.hxx"
#include "hyperdlg.hrc"
#include "hlmarkwn_def.hxx"
sal_Char const sHash[] = "#";
sal_Char const sFileScheme[] = INET_FILE_SCHEME;
/*************************************************************************
|*
|* Contructor / Destructor
|*
|************************************************************************/
SvxHyperlinkDocTp::SvxHyperlinkDocTp ( Window *pParent, const SfxItemSet& rItemSet)
: SvxHyperlinkTabPageBase ( pParent, CUI_RES( RID_SVXPAGE_HYPERLINK_DOCUMENT ), rItemSet ),
maGrpDocument ( this, CUI_RES (GRP_DOCUMENT) ),
maFtPath ( this, CUI_RES (FT_PATH_DOC) ),
maCbbPath ( this, INET_PROT_FILE ),
maBtFileopen ( this, CUI_RES (BTN_FILEOPEN) ),
maGrpTarget ( this, CUI_RES (GRP_TARGET) ),
maFtTarget ( this, CUI_RES (FT_TARGET_DOC) ),
maEdTarget ( this, CUI_RES (ED_TARGET_DOC) ),
maFtURL ( this, CUI_RES (FT_URL) ),
maFtFullURL ( this, CUI_RES (FT_FULL_URL) ),
maBtBrowse ( this, CUI_RES (BTN_BROWSE) ),
mbMarkWndOpen ( sal_False )
{
// Disable display of bitmap names.
maBtBrowse.EnableTextDisplay (false);
maBtFileopen.EnableTextDisplay (false);
InitStdControls();
FreeResource();
// Init URL-Box (pos&size, Open-Handler)
maCbbPath.SetPosSizePixel ( LogicToPixel( Point( COL_2, 15 ), MAP_APPFONT ),
LogicToPixel( Size ( 176 - COL_DIFF, 60), MAP_APPFONT ) );
maCbbPath.Show();
OUString aFileScheme( INET_FILE_SCHEME );
maCbbPath.SetBaseURL(aFileScheme);
maCbbPath.SetHelpId( HID_HYPERDLG_DOC_PATH );
SetExchangeSupport ();
// overload handlers
maBtFileopen.SetClickHdl ( LINK ( this, SvxHyperlinkDocTp, ClickFileopenHdl_Impl ) );
maBtBrowse.SetClickHdl ( LINK ( this, SvxHyperlinkDocTp, ClickTargetHdl_Impl ) );
maCbbPath.SetModifyHdl ( LINK ( this, SvxHyperlinkDocTp, ModifiedPathHdl_Impl ) );
maEdTarget.SetModifyHdl ( LINK ( this, SvxHyperlinkDocTp, ModifiedTargetHdl_Impl ) );
maCbbPath.SetLoseFocusHdl( LINK ( this, SvxHyperlinkDocTp, LostFocusPathHdl_Impl ) );
maBtBrowse.SetAccessibleRelationMemberOf( &maGrpTarget );
maBtBrowse.SetAccessibleRelationLabeledBy( &maFtTarget );
maBtFileopen.SetAccessibleRelationMemberOf( &maGrpDocument );
maBtFileopen.SetAccessibleRelationLabeledBy( &maFtPath );
maTimer.SetTimeoutHdl ( LINK ( this, SvxHyperlinkDocTp, TimeoutHdl_Impl ) );
}
SvxHyperlinkDocTp::~SvxHyperlinkDocTp ()
{
}
/*************************************************************************
|*
|* Fill all dialog-controls except controls in groupbox "more..."
|*
|************************************************************************/
void SvxHyperlinkDocTp::FillDlgFields(const OUString& rStrURL)
{
sal_Int32 nPos = rStrURL.indexOf(sHash);
// path
maCbbPath.SetText ( rStrURL.copy( 0, ( nPos == -1 ? rStrURL.getLength() : nPos ) ) );
// set target in document at editfield
OUString aStrMark;
if ( nPos != -1 && nPos < rStrURL.getLength()-1 )
aStrMark = rStrURL.copy( nPos+1, rStrURL.getLength() - nPos - 1 );
maEdTarget.SetText ( aStrMark );
ModifiedPathHdl_Impl ( NULL );
}
/*************************************************************************
|*
|* retrieve current url-string
|*
|************************************************************************/
OUString SvxHyperlinkDocTp::GetCurrentURL ()
{
// get data from dialog-controls
OUString aStrURL;
OUString aStrPath ( maCbbPath.GetText() );
const OUString aBaseURL ( maCbbPath.GetBaseURL() );
OUString aStrMark( maEdTarget.GetText() );
if ( aStrPath != aEmptyStr )
{
INetURLObject aURL( aStrPath );
if ( aURL.GetProtocol() != INET_PROT_NOT_VALID ) // maybe the path is already a valid
aStrURL = aStrPath; // hyperlink, then we can use this path directly
else
utl::LocalFileHelper::ConvertSystemPathToURL( aStrPath, aBaseURL, aStrURL );
//#105788# always create a URL even if it is not valid
if( aStrURL == aEmptyStr )
aStrURL = aStrPath;
}
if( aStrMark != aEmptyStr )
{
aStrURL += OUString( sHash );
aStrURL += aStrMark;
}
return aStrURL;
}
/*************************************************************************
|*
|* retrieve and prepare data from dialog-fields
|*
|************************************************************************/
void SvxHyperlinkDocTp::GetCurentItemData ( OUString& rStrURL, OUString& aStrName,
OUString& aStrIntName, OUString& aStrFrame,
SvxLinkInsertMode& eMode )
{
// get data from standard-fields
rStrURL = GetCurrentURL();
if( rStrURL.equalsIgnoreAsciiCase( sFileScheme ) )
rStrURL = "";
GetDataFromCommonFields( aStrName, aStrIntName, aStrFrame, eMode );
}
/*************************************************************************
|*
|* static method to create Tabpage
|*
|************************************************************************/
IconChoicePage* SvxHyperlinkDocTp::Create( Window* pWindow, const SfxItemSet& rItemSet )
{
return( new SvxHyperlinkDocTp( pWindow, rItemSet ) );
}
/*************************************************************************
|*
|* Set initial focus
|*
|************************************************************************/
void SvxHyperlinkDocTp::SetInitFocus()
{
maCbbPath.GrabFocus();
}
/*************************************************************************
|*
|* Click on imagebutton : fileopen
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ClickFileopenHdl_Impl)
{
// Open Fileopen-Dialog
::sfx2::FileDialogHelper aDlg(
com::sun::star::ui::dialogs::TemplateDescription::FILEOPEN_SIMPLE, 0,
GetParent() );
OUString aOldURL( GetCurrentURL() );
if( aOldURL.startsWithIgnoreAsciiCase( sFileScheme ) )
{
aDlg.SetDisplayDirectory( aOldURL );
}
DisableClose( sal_True );
ErrCode nError = aDlg.Execute();
DisableClose( sal_False );
if ( ERRCODE_NONE == nError )
{
OUString aURL( aDlg.GetPath() );
OUString aPath;
utl::LocalFileHelper::ConvertURLToSystemPath( aURL, aPath );
maCbbPath.SetBaseURL( aURL );
maCbbPath.SetText( aPath );
if ( aOldURL != GetCurrentURL() )
ModifiedPathHdl_Impl (NULL);
}
return( 0L );
}
/*************************************************************************
|*
|* Click on imagebutton : target
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ClickTargetHdl_Impl)
{
if ( GetPathType ( maStrURL ) == Type_ExistsFile ||
maStrURL.isEmpty() ||
maStrURL.equalsIgnoreAsciiCase( sFileScheme ) ||
maStrURL.startsWith( sHash ) )
{
mpMarkWnd->SetError( LERR_NOERROR );
EnterWait();
if ( maStrURL.equalsIgnoreAsciiCase( sFileScheme ) )
mpMarkWnd->RefreshTree ( aEmptyStr );
else
mpMarkWnd->RefreshTree ( maStrURL );
LeaveWait();
}
else
mpMarkWnd->SetError( LERR_DOCNOTOPEN );
ShowMarkWnd ();
return( 0L );
}
/*************************************************************************
|*
|* Contens of combobox "Path" modified
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ModifiedPathHdl_Impl)
{
maStrURL = GetCurrentURL();
maTimer.SetTimeout( 2500 );
maTimer.Start();
maFtFullURL.SetText( maStrURL );
return( 0L );
}
/*************************************************************************
|*
|* If path-field was modify, to browse the new doc after timeout
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, TimeoutHdl_Impl)
{
if ( IsMarkWndVisible() && ( GetPathType( maStrURL )==Type_ExistsFile ||
maStrURL.isEmpty() ||
maStrURL.equalsIgnoreAsciiCase( sFileScheme ) ) )
{
EnterWait();
if ( maStrURL.equalsIgnoreAsciiCase( sFileScheme ) )
mpMarkWnd->RefreshTree ( aEmptyStr );
else
mpMarkWnd->RefreshTree ( maStrURL );
LeaveWait();
}
return( 0L );
}
/*************************************************************************
|*
|* Contens of editfield "Target" modified
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, ModifiedTargetHdl_Impl)
{
maStrURL = GetCurrentURL();
if ( IsMarkWndVisible() )
mpMarkWnd->SelectEntry ( maEdTarget.GetText() );
maFtFullURL.SetText( maStrURL );
return( 0L );
}
/*************************************************************************
|*
|* editfield "Target" lost focus
|*
|************************************************************************/
IMPL_LINK_NOARG(SvxHyperlinkDocTp, LostFocusPathHdl_Impl)
{
maStrURL = GetCurrentURL();
maFtFullURL.SetText( maStrURL );
return (0L);
}
/*************************************************************************
|*
|* Get String from Bookmark-Wnd
|*
|************************************************************************/
void SvxHyperlinkDocTp::SetMarkStr ( const OUString& aStrMark )
{
maEdTarget.SetText ( aStrMark );
ModifiedTargetHdl_Impl ( NULL );
}
/*************************************************************************
|*
|* retrieve kind of pathstr
|*
|************************************************************************/
SvxHyperlinkDocTp::EPathType SvxHyperlinkDocTp::GetPathType ( const OUString& rStrPath )
{
INetURLObject aURL( rStrPath, INET_PROT_FILE );
if( aURL.HasError() )
return Type_Invalid;
else
return Type_ExistsFile;
}
/* vim:set shiftwidth=4 softtabstop=4 expandtab: */
<|endoftext|> |
<commit_before><commit_msg>remove UB from cyber base object pool test<commit_after><|endoftext|> |
<commit_before>#include "MatrixTransform.hpp"
#include "misc.hpp"
#include <cmath>
namespace yks {
mat3 rotate(const vec3& axis, float angle)
{
// Taken from Graphics Gems I (Section IX.6)
const float s = std::sin(angle);
const float c = std::cos(angle);
const float t = 1.f - c;
const float x = axis[0];
const float y = axis[1];
const float z = axis[2];
// A lot of common sub-expression optimization can be
// done here, but I'll leave that to the compiler.
mat3 m = {{
{t*x*x + c, t*x*y - s*z, t*x*z + s*y},
{t*y*x + s*z, t*y*y + c, t*y*z - s*x},
{t*z*x - s*y, t*z*y + s*x, t*z*z + c, }
}};
return m;
}
mat3 orient(const vec3& up, const vec3& forward) {
const vec3 z_axis = forward;
const vec3 x_axis = cross(z_axis, up);
const vec3 y_axis = cross(x_axis, z_axis);
return mat3{{
x_axis,
y_axis,
z_axis
}};
}
mat4 orthographic_proj(float left, float right, float bottom, float top, float z_near, float z_far)
{
vec3 t = mvec3(left + right, bottom + top, z_near + z_far) * -(1.f/2.f);
vec3 s = inverse(mvec3(right - left, top - bottom, z_far - z_near)) * 2.f;
return pad<4>(scale(s)) * translate(t);
}
mat4 frustrum_proj(float half_width, float half_height, float z_near, float z_far)
{
// x' * z = (F / W)*x;
// y' * z = (F / H)*y;
// z' * z = A*z + B*1;
// A = (F + N)/(F - N);
// B = (2 * F * N)/(N - F);
const float z_over_w = z_far / half_width;
const float z_over_h = z_far / half_height;
const float a = (z_far + z_near) / (z_far - z_near);
const float b = (2.f * z_far * z_near)/(z_near - z_far);
mat4 m = {{
{z_over_w, 0.f, 0.f, 0.f},
{ 0.f, z_over_h, 0.f, 0.f},
{ 0.f, 0.f, a, b },
{ 0.f, 0.f, 1.f, 0.f}
}};
return m;
}
mat4 perspective_proj(float vfov, float aspect, float z_near, float z_far)
{
float height = z_far * std::tanf(vfov * (pi / 180.f));
return frustrum_proj(height * aspect, height, z_near, z_far);
}
mat4 look_at(const vec3& up, const vec3& camera, const vec3& target)
{
return pad<4>(orient(up, normalized(target - camera))) * translate(-camera);
}
}
<commit_msg>Fix bug in orient() when vectors aren't perpendicular<commit_after>#include "MatrixTransform.hpp"
#include "misc.hpp"
#include <cmath>
namespace yks {
mat3 rotate(const vec3& axis, float angle)
{
// Taken from Graphics Gems I (Section IX.6)
const float s = std::sin(angle);
const float c = std::cos(angle);
const float t = 1.f - c;
const float x = axis[0];
const float y = axis[1];
const float z = axis[2];
// A lot of common sub-expression optimization can be
// done here, but I'll leave that to the compiler.
mat3 m = {{
{t*x*x + c, t*x*y - s*z, t*x*z + s*y},
{t*y*x + s*z, t*y*y + c, t*y*z - s*x},
{t*z*x - s*y, t*z*y + s*x, t*z*z + c, }
}};
return m;
}
mat3 orient(const vec3& up, const vec3& forward) {
const vec3 z_axis = forward;
const vec3 x_axis = normalized(cross(z_axis, up));
const vec3 y_axis = cross(x_axis, z_axis);
return mat3{{
x_axis,
y_axis,
z_axis
}};
}
mat4 orthographic_proj(float left, float right, float bottom, float top, float z_near, float z_far)
{
vec3 t = mvec3(left + right, bottom + top, z_near + z_far) * -(1.f/2.f);
vec3 s = inverse(mvec3(right - left, top - bottom, z_far - z_near)) * 2.f;
return pad<4>(scale(s)) * translate(t);
}
mat4 frustrum_proj(float half_width, float half_height, float z_near, float z_far)
{
// x' * z = (F / W)*x;
// y' * z = (F / H)*y;
// z' * z = A*z + B*1;
// A = (F + N)/(F - N);
// B = (2 * F * N)/(N - F);
const float z_over_w = z_far / half_width;
const float z_over_h = z_far / half_height;
const float a = (z_far + z_near) / (z_far - z_near);
const float b = (2.f * z_far * z_near)/(z_near - z_far);
mat4 m = {{
{z_over_w, 0.f, 0.f, 0.f},
{ 0.f, z_over_h, 0.f, 0.f},
{ 0.f, 0.f, a, b },
{ 0.f, 0.f, 1.f, 0.f}
}};
return m;
}
mat4 perspective_proj(float vfov, float aspect, float z_near, float z_far)
{
float height = z_far * std::tanf(vfov * (pi / 180.f));
return frustrum_proj(height * aspect, height, z_near, z_far);
}
mat4 look_at(const vec3& up, const vec3& camera, const vec3& target)
{
return pad<4>(orient(up, normalized(target - camera))) * translate(-camera);
}
}
<|endoftext|> |
<commit_before>///////////////////////////////////////////////////////////////////////////////
// Mat::const_row_col_iterator implementation //
///////////////////////////////////////////////////////////////////////////////
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator()
: M(NULL), current_pos(NULL), internal_row(0), internal_col(0)
{
// Technically this iterator is invalid (it may not point to a real element)
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const row_col_iterator& it)
: M(it.M), current_pos(it.current_pos), internal_col(it.col()), internal_row(it.row())
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const const_row_iterator& it)
: M(&it.M), current_pos(&it.M(it.row, it.col)), internal_col(it.col), internal_row(it.row)
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const row_iterator& it)
: M(&it.M), current_pos(&it.M(it.row, it.col)), internal_col(it.col), internal_row(it.row)
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const Mat<eT>& in_M, const uword row, const uword col)
: M(&in_M), current_pos(&in_M(row,col)), internal_row(row), internal_col(col)
{
// Nothing to do.
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator&
Mat<eT>::const_row_col_iterator::operator++()
{
current_pos++;
internal_row++;
// Check to see if we moved a column.
if(internal_row == M->n_rows)
{
internal_col++;
internal_row = 0;
}
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::const_row_col_iterator::operator++(int)
{
typename Mat<eT>::const_row_col_iterator temp(*this);
++(*this);
return temp;
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator&
Mat<eT>::const_row_col_iterator::operator--()
{
current_pos--;
internal_row--;
// Check to see if we moved a column.
if(internal_row == -1)
{
internal_col--;
internal_row = M->n_rows - 1;
}
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::const_row_col_iterator::operator--(int)
{
typename Mat<eT>::const_row_col_iterator temp(*this);
--(*this);
return temp;
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const const_iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const const_iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
///////////////////////////////////////////////////////////////////////////////
// Mat::row_col_iterator implementation //
///////////////////////////////////////////////////////////////////////////////
template<typename eT>
inline
Mat<eT>::row_col_iterator::row_col_iterator()
: M(NULL), current_pos(NULL), internal_row(0), internal_col(0)
{
// Technically this iterator is invalid (it may not point to a real element)
}
template<typename eT>
inline
Mat<eT>::row_col_iterator::row_col_iterator(const row_iterator& it)
: M(&it.M), current_pos(&it.M(it.row, it.col)), internal_col(it.col), internal_row(it.row)
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::row_col_iterator::row_col_iterator(Mat<eT>& in_M, const uword row, const uword col)
: M(&in_M), current_pos(&in_M(row,col)), internal_row(row), internal_col(col)
{
// Nothing to do.
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator&
Mat<eT>::row_col_iterator::operator++()
{
current_pos++;
internal_row++;
// Check to see if we moved a column.
if(internal_row == M->n_rows)
{
internal_col++;
internal_row = 0;
}
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::row_col_iterator::operator++(int)
{
typename Mat<eT>::row_col_iterator temp(*this);
++(*this);
return temp;
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator&
Mat<eT>::row_col_iterator::operator--()
{
current_pos--;
internal_row--;
// Check to see if we moved a column.
if(internal_row == -1)
{
internal_col--;
internal_row = M->n_rows - 1;
}
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::row_col_iterator::operator--(int)
{
typename Mat<eT>::row_col_iterator temp(*this);
--(*this);
return temp;
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const const_iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const const_iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
///////////////////////////////////////////////////////////////////////////////
// extended Mat functionality implementation //
///////////////////////////////////////////////////////////////////////////////
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::begin_row_col() const
{
return const_row_col_iterator(*this);
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::begin_row_col()
{
return row_col_iterator(*this);
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::end_row_col() const
{
return ++const_row_col_iterator(*this, n_rows - 1, n_cols - 1);
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::end_row_col()
{
return ++row_col_iterator(*this, n_rows - 1, n_cols - 1);
}
<commit_msg>Return statements for operator++() and operator--().<commit_after>///////////////////////////////////////////////////////////////////////////////
// Mat::const_row_col_iterator implementation //
///////////////////////////////////////////////////////////////////////////////
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator()
: M(NULL), current_pos(NULL), internal_row(0), internal_col(0)
{
// Technically this iterator is invalid (it may not point to a real element)
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const row_col_iterator& it)
: M(it.M), current_pos(it.current_pos), internal_col(it.col()), internal_row(it.row())
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const const_row_iterator& it)
: M(&it.M), current_pos(&it.M(it.row, it.col)), internal_col(it.col), internal_row(it.row)
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const row_iterator& it)
: M(&it.M), current_pos(&it.M(it.row, it.col)), internal_col(it.col), internal_row(it.row)
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::const_row_col_iterator::const_row_col_iterator(const Mat<eT>& in_M, const uword row, const uword col)
: M(&in_M), current_pos(&in_M(row,col)), internal_row(row), internal_col(col)
{
// Nothing to do.
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator&
Mat<eT>::const_row_col_iterator::operator++()
{
current_pos++;
internal_row++;
// Check to see if we moved a column.
if(internal_row == M->n_rows)
{
internal_col++;
internal_row = 0;
}
return *this;
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::const_row_col_iterator::operator++(int)
{
typename Mat<eT>::const_row_col_iterator temp(*this);
++(*this);
return temp;
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator&
Mat<eT>::const_row_col_iterator::operator--()
{
current_pos--;
internal_row--;
// Check to see if we moved a column.
if(internal_row == -1)
{
internal_col--;
internal_row = M->n_rows - 1;
}
return *this;
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::const_row_col_iterator::operator--(int)
{
typename Mat<eT>::const_row_col_iterator temp(*this);
--(*this);
return temp;
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const const_iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const const_iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator==(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::const_row_col_iterator::operator!=(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
///////////////////////////////////////////////////////////////////////////////
// Mat::row_col_iterator implementation //
///////////////////////////////////////////////////////////////////////////////
template<typename eT>
inline
Mat<eT>::row_col_iterator::row_col_iterator()
: M(NULL), current_pos(NULL), internal_row(0), internal_col(0)
{
// Technically this iterator is invalid (it may not point to a real element)
}
template<typename eT>
inline
Mat<eT>::row_col_iterator::row_col_iterator(const row_iterator& it)
: M(&it.M), current_pos(&it.M(it.row, it.col)), internal_col(it.col), internal_row(it.row)
{
// Nothing to do.
}
template<typename eT>
inline
Mat<eT>::row_col_iterator::row_col_iterator(Mat<eT>& in_M, const uword row, const uword col)
: M(&in_M), current_pos(&in_M(row,col)), internal_row(row), internal_col(col)
{
// Nothing to do.
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator&
Mat<eT>::row_col_iterator::operator++()
{
current_pos++;
internal_row++;
// Check to see if we moved a column.
if(internal_row == M->n_rows)
{
internal_col++;
internal_row = 0;
}
return *this;
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::row_col_iterator::operator++(int)
{
typename Mat<eT>::row_col_iterator temp(*this);
++(*this);
return temp;
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator&
Mat<eT>::row_col_iterator::operator--()
{
current_pos--;
internal_row--;
// Check to see if we moved a column.
if(internal_row == -1)
{
internal_col--;
internal_row = M->n_rows - 1;
}
return *this;
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::row_col_iterator::operator--(int)
{
typename Mat<eT>::row_col_iterator temp(*this);
--(*this);
return temp;
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const const_row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const row_col_iterator& rhs) const
{
return (rhs.current_pos == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const row_col_iterator& rhs) const
{
return (rhs.current_pos != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const const_iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const const_iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const iterator& rhs) const
{
return (rhs == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const iterator& rhs) const
{
return (rhs != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const const_row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator==(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) == current_pos);
}
template<typename eT>
inline bool
Mat<eT>::row_col_iterator::operator!=(const row_iterator& rhs) const
{
return (&rhs.M(rhs.row, rhs.col) != current_pos);
}
///////////////////////////////////////////////////////////////////////////////
// extended Mat functionality implementation //
///////////////////////////////////////////////////////////////////////////////
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::begin_row_col() const
{
return const_row_col_iterator(*this);
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::begin_row_col()
{
return row_col_iterator(*this);
}
template<typename eT>
inline typename Mat<eT>::const_row_col_iterator
Mat<eT>::end_row_col() const
{
return ++const_row_col_iterator(*this, n_rows - 1, n_cols - 1);
}
template<typename eT>
inline typename Mat<eT>::row_col_iterator
Mat<eT>::end_row_col()
{
return ++row_col_iterator(*this, n_rows - 1, n_cols - 1);
}
<|endoftext|> |
<commit_before>
#include <stddef.h> // Чтобы определить NULL
///////// Включения основного модуля module.h
#include "Module.h"
#include "Function_module.h"
#include <math.h>
#include <iostream>
#include <time.h> // для Рандомайзера
using namespace std;
// Опишу функцию вне класса чтобы можно было применять cout
FunctionResult* MathFunctionModule::executeFunction(regval functionId, regval *args){
cout << "Func executed" << endl;
if (!functionId) {
return NULL;
}
// эта конструкция чтобы создать заранее объект указатель на который будем возвращать
char ch4 = '1'; // имя надо будет поменять или просто что-то поменять. Но пока символ оставим в покое и буем работать с result.
rez = new FunctionResult(ch4);
// Уже не тестовое задание пробуем описать
switch (functionId) {
//первая функция pow - квадрат. 1-й аргумент возводимое, второй - степень.
case 1: // Тут вопрос про приведение типов
{
//C приведением типов
double arg1,arg2,resOfPow;
arg1=*args;
arg2=*(args+1);
resOfPow=pow(arg1,arg2);
rez->result = (int) resOfPow;
// Все сделали и выходим из свича
break;
}
case 2: // ABS модуль числа
{
/*C приведением типов*/
int resOfabs;
resOfabs = abs(*args);
rez->result = resOfabs;
// Все сделали и выходим из свича
break;
}
case 3: // FMOD Остаток от деления
{
int resOfmod;
resOfmod = (int) fmod(*args,*(args +1));
rez->result = resOfmod;
// Все сделали и выходим из свича
break;
}
case 4: // DIV Целочисленное деление
int resOfdiv;
resOfdiv = ( *args - (int)fmod(*args, *(args + 1)) ) / (*(args+1));
rez->result = resOfdiv;
// Все сделали и выходим из свича
break;
case 5: // Корень 2-й степени Результат будем выводить умноженным на 1000, потому что растет медленно(меняется медленно)
{
int resOfsqrt;
resOfsqrt = (int) (1000 * sqrt(*args));
rez->result = resOfsqrt;
// Все сделали и выходим из свича
break;
}
case 6: // Рандомное целое число
{
int resOfrand;
resOfrand = rand()%(*args) + (*(args+1)) ;
rez->result = resOfrand;
// Все сделали и выходим из свича
break;
}
case 7: // Синус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
int resOfsin;
resOfsin = (int) (1000 * sin(*args/1000)) ;
rez->result = resOfsin;
// Все сделали и выходим из свича
break;
}
case 8: // Косинус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
int resOfcos;
resOfcos = (int)(1000 * cos(*args/1000));
rez->result = resOfcos;
// Все сделали и выходим из свича
break;
}
case 9: // Тангенс Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
int resOftan;
resOftan = (int)(1000 * tan(*args / 1000));
rez->result = resOftan;
// Все сделали и выходим из свича
break;
}
case 10: // АркСинус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
int resOfasin;
resOfasin = (int)(1000 * asin(*args / 1000));
rez->result = resOfasin;
// Все сделали и выходим из свича
break;
}
case 11: // АркКосинус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
int resOfacos;
resOfacos = (int)(1000 * acos(*args / 1000));
rez->result = resOfacos;
// Все сделали и выходим из свича
break;
}
case 12: // АркТангенс Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
int resOfatan;
resOfatan = (int)(1000 * atan(*args / 1000));
rez->result = resOfatan;
// Все сделали и выходим из свича
break;
}
case 13: // Экспонента Растет быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000
{
int resOfexp;
resOfexp = (int)exp(*args / 1000);
rez->result = resOfexp;
// Все сделали и выходим из свича
break;
}
case 14: // Логарифм Натуральный Растет медленно поэтому вывод умножим на 1000
{
int resOflog;
resOflog = (int)( 1000* log(*args));
rez->result = resOflog;
// Все сделали и выходим из свича
break;
}
case 15: // Десятичный логарифм Растет медленно поэтому вывод умножим на 1000
{
int resOflog10;
resOflog10 = (int) (1000 * log10(*args));
rez->result = resOflog10;
// Все сделали и выходим из свича
break;
}
}; // Конец switch
return rez;
};
int main(){
int test;
test = 1;
cout << test << endl;
regval *arg1;
regval x;
x = 1;
arg1 = &x;
regval TwoArgs[] = {2,3};
regval absTestMas[] = { -14 };
regval fmodTestMas[] = { 7, 4 };
regval divTestMas[] = { 9, 4 };
regval randTestMas[] = { 10, 1 };
regval SiCoTanTestMas[] = {1};
MathFunctionModule newObject;
FunctionResult *FRobject;
// проверка возведения в степень
FRobject = newObject.executeFunction(1, TwoArgs); // не забываем что этот объект ссылается на свойство newObject.
cout << FRobject << endl;
cout << FRobject->type << endl;
cout << FRobject->result << endl;
// Проверка получения абсолютной величины
FRobject = newObject.executeFunction(2, absTestMas); // не забываем что этот объект ссылается на свойство newObject.
cout << FRobject << endl;
cout << FRobject->type << endl;
cout << FRobject->result << endl;
// Проверка остатка от деления
FRobject = newObject.executeFunction(3, fmodTestMas); // не забываем что этот объект ссылается на свойство newObject.
cout << FRobject << endl;
cout << FRobject->type << endl;
cout << FRobject->result << endl;
// Проверка целочисленного деления на том же массиве
FRobject = newObject.executeFunction(4, divTestMas); // не забываем что этот объект ссылается на свойство newObject.
cout << FRobject << endl;
cout << FRobject->type << endl;
cout << FRobject->result << endl;
cout << "- - - " << newObject.executeFunction(4, divTestMas)->result + newObject.executeFunction(4, divTestMas)->result << endl;
// Проверка Установка рандомайзера. не важно что передаем в аргументах
FRobject = newObject.executeFunction(5, divTestMas); // не забываем что этот объект ссылается на свойство newObject.
cout << FRobject << endl;
cout << FRobject->type << endl;
cout << FRobject->result << endl;
// Проверяем рандомайзер
FRobject = newObject.executeFunction(6, randTestMas); // не забываем что этот объект ссылается на свойство newObject.
cout << FRobject->result << endl;
FRobject = newObject.executeFunction(6, randTestMas); // не забываем что этот объект ссылается на свойство newObject.
cout << FRobject->result << endl;
return 0;
}
<commit_msg>Update math_function_module.cpp<commit_after>#include <stddef.h> // Чтобы определить NULL
#include <time.h> // для Рандомайзера
///////// Включения основного модуля module.h
#include "Module.h"
#include "Function_Module.h"
#include "Math_Function_Module.h"
#include <math.h>
#include <iostream>
//using namespace std;
////////////// Установка Глобальных переменных.
// GLOBAL VARIABLES
int COUNT_MATH_FUNCTIONS = 15;
// Опишем макросс который будет заполнять наш массив структур с информацией о функциях. Ия функции, Присваивает уникальный индекс, число параметров и дает ли исключение.
#define ADD_MATH_FUNCTION(FUNCTION_NAME, COUNT_PARAMS, GIVE_EXCEPTION) \
math_functions[function_id] = new FunctionData; \
math_functions[function_id]->command_index = function_id + 1; \
math_functions[function_id]->count_params = COUNT_PARAMS; \
math_functions[function_id]->give_exception = GIVE_EXCEPTION; \
math_functions[function_id]->name = FUNCTION_NAME; \
function_id++;
// важная часть чтобы был уникальный параметр
// начинается от нуля поэтому такой вид. В конструкторе перед использованием function_id будет присвоен ноль.
/////////////////////////////////////////////////////////////////////////////////
// Опишем макросс который все наши функции заполнит/ Добавил Функцию - Увеличивай их число COUNT_MATH_FUNCTIONS. А то удалишь нафиг какой-нить процесс в памяти.
#define DEFINE_ALL_FUNCTIONS \
ADD_MATH_FUNCTION("pow", 2,false) \
ADD_MATH_FUNCTION("abs", 1,false) \
ADD_MATH_FUNCTION("mod", 2,false) \
ADD_MATH_FUNCTION("div", 2,false) \
ADD_MATH_FUNCTION("sqrt", 1,false) \
ADD_MATH_FUNCTION("rand", 1,false) \
ADD_MATH_FUNCTION("sin", 1,false) \
ADD_MATH_FUNCTION("cos", 1,false) \
ADD_MATH_FUNCTION("tan", 1,false) \
ADD_MATH_FUNCTION("asin", 1,false) \
ADD_MATH_FUNCTION("acos", 1,false) \
ADD_MATH_FUNCTION("atan", 1,false) \
ADD_MATH_FUNCTION("exp", 1,false) \
ADD_MATH_FUNCTION("log", 1,false) \
ADD_MATH_FUNCTION("log10",1,false)
// Конец макроса
// Далее описание методов класса МathFunctionModule
// Метод UID
const char* MathFunctionModule::getUID() {
return "Math_Functions_dll";
};
// метод получения данных о наших функциях
FunctionData** MathFunctionModule::getFunctions(int *count_functions){ // Эта функция даст указатель на массив струкктур где описаны функции
*count_functions = COUNT_MATH_FUNCTIONS; // Присваиваем в переменную(параметр функции) число наших функций
return math_functions;
};
// Конструктор класса
MathFunctionModule::MathFunctionModule() {// В этом конструкторе сразу создадим массив структур
math_functions = new FunctionData*[COUNT_MATH_FUNCTIONS];// Использует глобальную переменную. Это выделение памяти под массив указателей на структуры FunctionData из MSDN
regval function_id = 0; // С этим идентефикатором работает DEFINE_ALL_FUNCTIONS
srand(time(NULL)); // зададим сразу рандомайзхер - вдруг пригодится
DEFINE_ALL_FUNCTIONS
};
// Деструктор напишем отдельным методом. Он удалит структуры с нашими функциями и потом сам оъект.
void MathFunctionModule::destroy() {
for (int j = 0; j < COUNT_MATH_FUNCTIONS; ++j) {
delete math_functions[j];
}
delete[] math_functions;
delete this;
};
// Метод - выполнить математическую функцию
FunctionResult* MathFunctionModule::executeFunction(regval functionId, regval *args){
if ( (functionId<1) || (functionId >15) ) {
return NULL;
}
// эта конструкция чтобы создать заранее объект указатель на который будем возвращать
char ch4 = '1'; // имя надо будет поменять или просто что-то поменять. Но пока символ оставим в покое и буем работать с result.
rez = new FunctionResult(ch4);
// Уже не тестовое задание пробуем описать
switch (functionId) {
//первая функция pow - квадрат. 1-й аргумент возводимое, второй - степень.
case 1:
{
rez->result = (int) pow((double) *args, (double) (*(args+1)) );
// Все сделали и выходим из свича
break;
}
case 2: // ABS модуль числа
{
rez->result = abs(*args);
// Все сделали и выходим из свича
break;
}
case 3: // FMOD Остаток от деления
{
rez->result = (int)fmod(*args, *(args + 1));
// Все сделали и выходим из свича
break;
}
case 4: // DIV Целочисленное деление
rez->result = (*args - (int)fmod(*args, *(args + 1))) / (*(args + 1));
// Все сделали и выходим из свича
break;
case 5: // Корень 2-й степени Результат будем выводить умноженным на 1000, потому что растет медленно(меняется медленно)
{
rez->result = (int)(1000 * sqrt(*args));
// Все сделали и выходим из свича
break;
}
case 6: // Рандомное целое число
{
rez->result = rand() % (*args) + (*(args + 1));
// Все сделали и выходим из свича
break;
}
case 7: // Синус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
rez->result = (int)(1000 * sin(((double)*args) / 1000));
// Все сделали и выходим из свича
break;
}
case 8: // Косинус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
rez->result = (int)(1000 * cos(((double)*args) / 1000));
// Все сделали и выходим из свича
break;
}
case 9: // Тангенс Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
rez->result = (int)(1000 * tan(((double)*args) / 1000));
// Все сделали и выходим из свича
break;
}
case 10: // АркСинус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
rez->result = (int)(1000 * asin(((double)*args) / 1000));
// Все сделали и выходим из свича
break;
}
case 11: // АркКосинус Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
rez->result = (int)(1000 * acos(((double)*args) / 1000));
// Все сделали и выходим из свича
break;
}
case 12: // АркТангенс Изменяется быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000 и выводить будем умножив на 1000, потому что быстро меняется в малых пределах
{
rez->result = (int)(1000 * atan(((double)*args) / 1000));
// Все сделали и выходим из свича
break;
}
case 13: // Экспонента Растет быстро поэтому ввод просим умножить на 1000 а в вычислениях введенное будем делить на 1000
{
rez->result = (int)exp(((double)*args) / 1000);
// Все сделали и выходим из свича
break;
}
case 14: // Логарифм Натуральный Растет медленно поэтому вывод умножим на 1000
{
rez->result == (int)(1000 * log((double)*args));
// Все сделали и выходим из свича
break;
}
case 15: // Десятичный логарифм Растет медленно поэтому вывод умножим на 1000
{
rez->result = (int)(1000 * log10((double)*args));
// Все сделали и выходим из свича
break;
}
}; // Конец switch
return rez;
};
__declspec(dllexport) FunctionModule* getFunctionModuleObject() { // Нужная нам функция, вызвав ее в программе мы должны получить доступ к математическим функциям. Видимо определить их имена и т.д.
return new MathFunctionModule();
};
<|endoftext|> |
<commit_before>/*=========================================================================
*
* Copyright Insight Software Consortium
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0.txt
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*=========================================================================*/
#include "itkTimeGainCompensationImageFilter.h"
#include "itkCurvilinearArraySpecialCoordinatesImage.h"
#include "itkBModeImageFilter.h"
#include "itkCastImageFilter.h"
#include "itkImageFileReader.h"
#include "itkImageFileWriter.h"
#include "itkResampleImageFilter.h"
#include "itkTestingMacros.h"
int itkTimeGainCompensationImageFilterTest( int argc, char * argv[] )
{
if( argc < 3 )
{
std::cerr << "Usage: " << argv[0];
std::cerr << " inputImage outputImage";
std::cerr << std::endl;
return EXIT_FAILURE;
}
const char * inputImageFileName = argv[1];
const char * outputImageFileName = argv[2];
const unsigned int Dimension = 2;
typedef signed short IntegerPixelType;
typedef itk::CurvilinearArraySpecialCoordinatesImage< IntegerPixelType, Dimension > IntegerImageType;
typedef float RealPixelType;
typedef itk::CurvilinearArraySpecialCoordinatesImage< RealPixelType, Dimension > RealImageType;
typedef itk::Image< RealPixelType, Dimension > ScanConvertedImageType;
typedef itk::ImageFileReader< IntegerImageType > ReaderType;
ReaderType::Pointer reader = ReaderType::New();
reader->SetFileName( inputImageFileName );
typedef itk::TimeGainCompensationImageFilter< IntegerImageType > TGCFilterType;
TGCFilterType::Pointer tgcFilter = TGCFilterType::New();
tgcFilter->SetInput( reader->GetOutput() );
typedef TGCFilterType::GainType GainType;
GainType gain = tgcFilter->GetGain();
TEST_SET_GET_VALUE( 1.0, gain(0, 1) );
// Invalid number of columns
gain.SetSize( 4, 3 );
tgcFilter->SetGain( gain );
TRY_EXPECT_EXCEPTION( tgcFilter->Update() );
// Invalid number of rows
gain.SetSize( 1, 2 );
tgcFilter->SetGain( gain );
TRY_EXPECT_EXCEPTION( tgcFilter->Update() );
// Depths are not ascending
gain.SetSize( 3, 2 );
gain( 0, 0 ) = 0.0;
gain( 0, 1 ) = 1.0;
gain( 1, 0 ) = 2000.0;
gain( 1, 1 ) = 3.0;
gain( 2, 0 ) = 1000.0;
gain( 2, 1 ) = 5.0;
tgcFilter->SetGain( gain );
TRY_EXPECT_EXCEPTION( tgcFilter->Update() );
gain( 1, 0 ) = 1000.0;
gain( 2, 0 ) = 2000.0;
tgcFilter->SetGain( gain );
typedef itk::CastImageFilter< IntegerImageType, RealImageType > CasterType;
CasterType::Pointer caster = CasterType::New();
caster->SetInput( tgcFilter->GetOutput() );
typedef itk::BModeImageFilter< RealImageType, RealImageType > BModeFilterType;
BModeFilterType::Pointer bmodeFilter = BModeFilterType::New();
bmodeFilter->SetInput( caster->GetOutput() );
try
{
bmodeFilter->Update();
}
catch( itk::ExceptionObject & error )
{
std::cerr << "Error: " << error << std::endl;
return EXIT_FAILURE;
}
tgcFilter->Print( std::cout );
RealImageType::Pointer curvilinearArrayImage = bmodeFilter->GetOutput();
curvilinearArrayImage->DisconnectPipeline();
const RealImageType::SizeType inputSize = curvilinearArrayImage->GetLargestPossibleRegion().GetSize();
const double lateralAngularSeparation = (vnl_math::pi / 2.0 + 0.5) /
(inputSize[1] - 1);
curvilinearArrayImage->SetLateralAngularSeparation( lateralAngularSeparation );
const double radiusStart = 7.0;
const double radiusStop = 112.5;
curvilinearArrayImage->SetFirstSampleDistance( radiusStart );
curvilinearArrayImage->SetRadiusSampleSize( (radiusStop - radiusStart) / (inputSize[0] -1) );
typedef itk::ResampleImageFilter< RealImageType, ScanConvertedImageType > ResamplerType;
ResamplerType::Pointer resampler = ResamplerType::New();
resampler->SetInput( curvilinearArrayImage );
RealImageType::SizeType outputSize;
outputSize[0] = 800;
outputSize[1] = 800;
resampler->SetSize( outputSize );
RealImageType::SpacingType outputSpacing;
outputSpacing.Fill( 0.15 );
resampler->SetOutputSpacing( outputSpacing );
RealImageType::PointType outputOrigin;
outputOrigin[0] = outputSize[0] * outputSpacing[0] / -2.0;
outputOrigin[1] = radiusStart * std::cos( vnl_math::pi / 4.0 );
resampler->SetOutputOrigin( outputOrigin );
typedef itk::ImageFileWriter< ScanConvertedImageType > WriterType;
//typedef itk::ImageFileWriter< RealImageType > WriterType;
WriterType::Pointer writer = WriterType::New();
writer->SetFileName( outputImageFileName );
writer->SetInput( resampler->GetOutput() );
try
{
writer->Update();
}
catch( itk::ExceptionObject & error )
{
std::cerr << "Error: " << error << std::endl;
return EXIT_FAILURE;
}
return EXIT_SUCCESS;
}
<commit_msg>ENH: Decrease the TGC test output image size.<commit_after>/*=========================================================================
*
* Copyright Insight Software Consortium
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0.txt
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*=========================================================================*/
#include "itkTimeGainCompensationImageFilter.h"
#include "itkCurvilinearArraySpecialCoordinatesImage.h"
#include "itkBModeImageFilter.h"
#include "itkCastImageFilter.h"
#include "itkRescaleIntensityImageFilter.h"
#include "itkImageFileReader.h"
#include "itkImageFileWriter.h"
#include "itkResampleImageFilter.h"
#include "itkTestingMacros.h"
int itkTimeGainCompensationImageFilterTest( int argc, char * argv[] )
{
if( argc < 3 )
{
std::cerr << "Usage: " << argv[0];
std::cerr << " inputImage outputImage";
std::cerr << std::endl;
return EXIT_FAILURE;
}
const char * inputImageFileName = argv[1];
const char * outputImageFileName = argv[2];
const unsigned int Dimension = 2;
typedef signed short IntegerPixelType;
typedef itk::CurvilinearArraySpecialCoordinatesImage< IntegerPixelType, Dimension > IntegerImageType;
typedef float RealPixelType;
typedef itk::CurvilinearArraySpecialCoordinatesImage< RealPixelType, Dimension > RealImageType;
typedef itk::Image< RealPixelType, Dimension > ScanConvertedImageType;
typedef itk::ImageFileReader< IntegerImageType > ReaderType;
ReaderType::Pointer reader = ReaderType::New();
reader->SetFileName( inputImageFileName );
typedef itk::TimeGainCompensationImageFilter< IntegerImageType > TGCFilterType;
TGCFilterType::Pointer tgcFilter = TGCFilterType::New();
tgcFilter->SetInput( reader->GetOutput() );
typedef TGCFilterType::GainType GainType;
GainType gain = tgcFilter->GetGain();
TEST_SET_GET_VALUE( 1.0, gain(0, 1) );
// Invalid number of columns
gain.SetSize( 4, 3 );
tgcFilter->SetGain( gain );
TRY_EXPECT_EXCEPTION( tgcFilter->Update() );
// Invalid number of rows
gain.SetSize( 1, 2 );
tgcFilter->SetGain( gain );
TRY_EXPECT_EXCEPTION( tgcFilter->Update() );
// Depths are not ascending
gain.SetSize( 3, 2 );
gain( 0, 0 ) = 0.0;
gain( 0, 1 ) = 1.0;
gain( 1, 0 ) = 2000.0;
gain( 1, 1 ) = 3.0;
gain( 2, 0 ) = 1000.0;
gain( 2, 1 ) = 5.0;
tgcFilter->SetGain( gain );
TRY_EXPECT_EXCEPTION( tgcFilter->Update() );
gain( 1, 0 ) = 1000.0;
gain( 2, 0 ) = 2000.0;
tgcFilter->SetGain( gain );
typedef itk::CastImageFilter< IntegerImageType, RealImageType > CasterType;
CasterType::Pointer caster = CasterType::New();
caster->SetInput( tgcFilter->GetOutput() );
typedef itk::BModeImageFilter< RealImageType, RealImageType > BModeFilterType;
BModeFilterType::Pointer bmodeFilter = BModeFilterType::New();
bmodeFilter->SetInput( caster->GetOutput() );
try
{
bmodeFilter->Update();
}
catch( itk::ExceptionObject & error )
{
std::cerr << "Error: " << error << std::endl;
return EXIT_FAILURE;
}
tgcFilter->Print( std::cout );
RealImageType::Pointer curvilinearArrayImage = bmodeFilter->GetOutput();
curvilinearArrayImage->DisconnectPipeline();
const RealImageType::SizeType inputSize = curvilinearArrayImage->GetLargestPossibleRegion().GetSize();
const double lateralAngularSeparation = (vnl_math::pi / 2.0 + 0.5) /
(inputSize[1] - 1);
curvilinearArrayImage->SetLateralAngularSeparation( lateralAngularSeparation );
const double radiusStart = 7.0;
const double radiusStop = 112.5;
curvilinearArrayImage->SetFirstSampleDistance( radiusStart );
curvilinearArrayImage->SetRadiusSampleSize( (radiusStop - radiusStart) / (inputSize[0] -1) );
typedef itk::ResampleImageFilter< RealImageType, ScanConvertedImageType > ResamplerType;
ResamplerType::Pointer resampler = ResamplerType::New();
resampler->SetInput( curvilinearArrayImage );
RealImageType::SizeType outputSize;
outputSize[0] = 400;
outputSize[1] = 400;
resampler->SetSize( outputSize );
RealImageType::SpacingType outputSpacing;
outputSpacing.Fill( 0.30 );
resampler->SetOutputSpacing( outputSpacing );
RealImageType::PointType outputOrigin;
outputOrigin[0] = outputSize[0] * outputSpacing[0] / -2.0;
outputOrigin[1] = radiusStart * std::cos( vnl_math::pi / 4.0 );
resampler->SetOutputOrigin( outputOrigin );
typedef itk::Image< unsigned char, Dimension > OutputImageType;
typedef itk::RescaleIntensityImageFilter< ScanConvertedImageType, OutputImageType > RescalerType;
RescalerType::Pointer rescaler = RescalerType::New();
rescaler->SetInput( resampler->GetOutput() );
typedef itk::ImageFileWriter< OutputImageType > WriterType;
WriterType::Pointer writer = WriterType::New();
writer->SetFileName( outputImageFileName );
writer->SetInput( rescaler->GetOutput() );
try
{
writer->Update();
}
catch( itk::ExceptionObject & error )
{
std::cerr << "Error: " << error << std::endl;
return EXIT_FAILURE;
}
return EXIT_SUCCESS;
}
<|endoftext|> |
<commit_before>/****************************************************************************
**
** Copyright (C) 2011 Nokia Corporation and/or its subsidiary(-ies).
** All rights reserved.
** Contact: Nokia Corporation (qt-info@nokia.com)
**
** This file is part of the test suite of the Qt Toolkit.
**
** $QT_BEGIN_LICENSE:LGPL$
** GNU Lesser General Public License Usage
** This file may be used under the terms of the GNU Lesser General Public
** License version 2.1 as published by the Free Software Foundation and
** appearing in the file LICENSE.LGPL included in the packaging of this
** file. Please review the following information to ensure the GNU Lesser
** General Public License version 2.1 requirements will be met:
** http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html.
**
** In addition, as a special exception, Nokia gives you certain additional
** rights. These rights are described in the Nokia Qt LGPL Exception
** version 1.1, included in the file LGPL_EXCEPTION.txt in this package.
**
** GNU General Public License Usage
** Alternatively, this file may be used under the terms of the GNU General
** Public License version 3.0 as published by the Free Software Foundation
** and appearing in the file LICENSE.GPL included in the packaging of this
** file. Please review the following information to ensure the GNU General
** Public License version 3.0 requirements will be met:
** http://www.gnu.org/copyleft/gpl.html.
**
** Other Usage
** Alternatively, this file may be used in accordance with the terms and
** conditions contained in a signed written agreement between you and Nokia.
**
**
**
**
**
** $QT_END_LICENSE$
**
****************************************************************************/
#include <qtest.h>
#include <QLibraryInfo>
#include <QDir>
#include <QProcess>
#include <QDebug>
#include "qmlruntime.h"
#include <QDeclarativeView>
#include <QSGView>
#include <QDeclarativeError>
#ifdef Q_OS_SYMBIAN
// In Symbian OS test data is located in applications private dir
#define SRCDIR "."
#endif
class tst_examples : public QObject
{
Q_OBJECT
public:
tst_examples();
private slots:
void examples_data();
void examples();
void sgexamples_data();
void sgexamples();
void namingConvention();
private:
QStringList excludedDirs;
void namingConvention(const QDir &);
QStringList findQmlFiles(const QDir &);
};
tst_examples::tst_examples()
{
// Add directories you want excluded here
excludedDirs << "doc/src/snippets/declarative/visualdatamodel_rootindex";
excludedDirs << "doc/src/snippets/declarative/qtbinding";
excludedDirs << "doc/src/snippets/declarative/imports";
#ifdef QT_NO_WEBKIT
excludedDirs << "examples/declarative/modelviews/webview";
excludedDirs << "demos/declarative/webbrowser";
excludedDirs << "doc/src/snippets/declarative/webview";
#endif
#ifdef QT_NO_XMLPATTERNS
excludedDirs << "examples/declarative/xml/xmldata";
excludedDirs << "demos/declarative/twitter";
excludedDirs << "demos/declarative/flickr";
excludedDirs << "demos/declarative/photoviewer";
#endif
}
/*
This tests that the demos and examples follow the naming convention required
to have them tested by the examples() test.
*/
void tst_examples::namingConvention(const QDir &d)
{
for (int ii = 0; ii < excludedDirs.count(); ++ii) {
QString s = excludedDirs.at(ii);
if (d.absolutePath().endsWith(s))
return;
}
QStringList files = d.entryList(QStringList() << QLatin1String("*.qml"),
QDir::Files);
bool seenQml = !files.isEmpty();
bool seenLowercase = false;
foreach (const QString &file, files) {
if (file.at(0).isLower())
seenLowercase = true;
}
if (!seenQml) {
QStringList dirs = d.entryList(QDir::Dirs | QDir::NoDotAndDotDot |
QDir::NoSymLinks);
foreach (const QString &dir, dirs) {
QDir sub = d;
sub.cd(dir);
namingConvention(sub);
}
} else if(!seenLowercase) {
QTest::qFail(QString("Directory " + d.absolutePath() + " violates naming convention").toLatin1().constData(), __FILE__, __LINE__);
}
}
void tst_examples::namingConvention()
{
QString examples = QLibraryInfo::location(QLibraryInfo::ExamplesPath);
QString demos = QLibraryInfo::location(QLibraryInfo::DemosPath);
namingConvention(QDir(examples));
namingConvention(QDir(demos));
}
QStringList tst_examples::findQmlFiles(const QDir &d)
{
for (int ii = 0; ii < excludedDirs.count(); ++ii) {
QString s = excludedDirs.at(ii);
if (d.absolutePath().endsWith(s))
return QStringList();
}
QStringList rv;
QStringList cppfiles = d.entryList(QStringList() << QLatin1String("*.cpp"), QDir::Files);
if (cppfiles.isEmpty()) {
QStringList files = d.entryList(QStringList() << QLatin1String("*.qml"),
QDir::Files);
foreach (const QString &file, files) {
if (file.at(0).isLower()) {
rv << d.absoluteFilePath(file);
}
}
}
QStringList dirs = d.entryList(QDir::Dirs | QDir::NoDotAndDotDot |
QDir::NoSymLinks);
foreach (const QString &dir, dirs) {
QDir sub = d;
sub.cd(dir);
rv << findQmlFiles(sub);
}
return rv;
}
/*
This test runs all the examples in the declarative UI source tree and ensures
that they start and exit cleanly.
Examples are any .qml files under the examples/ or demos/ directory that start
with a lower case letter.
*/
void tst_examples::examples_data()
{
QTest::addColumn<QString>("file");
QString examples = QLatin1String(SRCDIR) + "/../../../../demos/declarative/";
QString demos = QLatin1String(SRCDIR) + "/../../../../examples/declarative/";
QString snippets = QLatin1String(SRCDIR) + "/../../../../doc/src/snippets/";
QStringList files;
files << findQmlFiles(QDir(examples));
files << findQmlFiles(QDir(demos));
files << findQmlFiles(QDir(snippets));
foreach (const QString &file, files)
QTest::newRow(qPrintable(file)) << file;
}
static void silentErrorsMsgHandler(QtMsgType, const char *)
{
}
void tst_examples::examples()
{
QFETCH(QString, file);
QDeclarativeViewer viewer;
QtMsgHandler old = qInstallMsgHandler(silentErrorsMsgHandler);
QVERIFY(viewer.open(file));
qInstallMsgHandler(old);
if (viewer.view()->status() == QDeclarativeView::Error)
qWarning() << viewer.view()->errors();
QCOMPARE(viewer.view()->status(), QDeclarativeView::Ready);
viewer.show();
QTest::qWaitForWindowShown(&viewer);
}
void tst_examples::sgexamples_data()
{
examples_data();
}
void tst_examples::sgexamples()
{
qputenv("QMLSCENE_IMPORT_NAME", "quick1");
QFETCH(QString, file);
QSGView view;
QtMsgHandler old = qInstallMsgHandler(silentErrorsMsgHandler);
view.setSource(file);
qInstallMsgHandler(old);
if (view.status() == QSGView::Error)
qWarning() << view.errors();
QCOMPARE(view.status(), QSGView::Ready);
view.show();
QTest::qWaitForWindowShown(&view);
}
QTEST_MAIN(tst_examples)
#include "tst_examples.moc"
<commit_msg>Improve failure message of tst_examples::namingConvention<commit_after>/****************************************************************************
**
** Copyright (C) 2011 Nokia Corporation and/or its subsidiary(-ies).
** All rights reserved.
** Contact: Nokia Corporation (qt-info@nokia.com)
**
** This file is part of the test suite of the Qt Toolkit.
**
** $QT_BEGIN_LICENSE:LGPL$
** GNU Lesser General Public License Usage
** This file may be used under the terms of the GNU Lesser General Public
** License version 2.1 as published by the Free Software Foundation and
** appearing in the file LICENSE.LGPL included in the packaging of this
** file. Please review the following information to ensure the GNU Lesser
** General Public License version 2.1 requirements will be met:
** http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html.
**
** In addition, as a special exception, Nokia gives you certain additional
** rights. These rights are described in the Nokia Qt LGPL Exception
** version 1.1, included in the file LGPL_EXCEPTION.txt in this package.
**
** GNU General Public License Usage
** Alternatively, this file may be used under the terms of the GNU General
** Public License version 3.0 as published by the Free Software Foundation
** and appearing in the file LICENSE.GPL included in the packaging of this
** file. Please review the following information to ensure the GNU General
** Public License version 3.0 requirements will be met:
** http://www.gnu.org/copyleft/gpl.html.
**
** Other Usage
** Alternatively, this file may be used in accordance with the terms and
** conditions contained in a signed written agreement between you and Nokia.
**
**
**
**
**
** $QT_END_LICENSE$
**
****************************************************************************/
#include <qtest.h>
#include <QLibraryInfo>
#include <QDir>
#include <QProcess>
#include <QDebug>
#include "qmlruntime.h"
#include <QDeclarativeView>
#include <QSGView>
#include <QDeclarativeError>
#ifdef Q_OS_SYMBIAN
// In Symbian OS test data is located in applications private dir
#define SRCDIR "."
#endif
class tst_examples : public QObject
{
Q_OBJECT
public:
tst_examples();
private slots:
void examples_data();
void examples();
void sgexamples_data();
void sgexamples();
void namingConvention();
private:
QStringList excludedDirs;
void namingConvention(const QDir &);
QStringList findQmlFiles(const QDir &);
};
tst_examples::tst_examples()
{
// Add directories you want excluded here
excludedDirs << "doc/src/snippets/declarative/visualdatamodel_rootindex";
excludedDirs << "doc/src/snippets/declarative/qtbinding";
excludedDirs << "doc/src/snippets/declarative/imports";
#ifdef QT_NO_WEBKIT
excludedDirs << "examples/declarative/modelviews/webview";
excludedDirs << "demos/declarative/webbrowser";
excludedDirs << "doc/src/snippets/declarative/webview";
#endif
#ifdef QT_NO_XMLPATTERNS
excludedDirs << "examples/declarative/xml/xmldata";
excludedDirs << "demos/declarative/twitter";
excludedDirs << "demos/declarative/flickr";
excludedDirs << "demos/declarative/photoviewer";
#endif
}
/*
This tests that the demos and examples follow the naming convention required
to have them tested by the examples() test.
*/
void tst_examples::namingConvention(const QDir &d)
{
for (int ii = 0; ii < excludedDirs.count(); ++ii) {
QString s = excludedDirs.at(ii);
if (d.absolutePath().endsWith(s))
return;
}
QStringList files = d.entryList(QStringList() << QLatin1String("*.qml"),
QDir::Files);
bool seenQml = !files.isEmpty();
bool seenLowercase = false;
foreach (const QString &file, files) {
if (file.at(0).isLower())
seenLowercase = true;
}
if (!seenQml) {
QStringList dirs = d.entryList(QDir::Dirs | QDir::NoDotAndDotDot |
QDir::NoSymLinks);
foreach (const QString &dir, dirs) {
QDir sub = d;
sub.cd(dir);
namingConvention(sub);
}
} else if(!seenLowercase) {
QFAIL(qPrintable(QString(
"Directory %1 violates naming convention; expected at least one qml file "
"starting with lower case, got: %2"
).arg(d.absolutePath()).arg(files.join(","))));
}
}
void tst_examples::namingConvention()
{
QString examples = QLibraryInfo::location(QLibraryInfo::ExamplesPath);
QString demos = QLibraryInfo::location(QLibraryInfo::DemosPath);
namingConvention(QDir(examples));
namingConvention(QDir(demos));
}
QStringList tst_examples::findQmlFiles(const QDir &d)
{
for (int ii = 0; ii < excludedDirs.count(); ++ii) {
QString s = excludedDirs.at(ii);
if (d.absolutePath().endsWith(s))
return QStringList();
}
QStringList rv;
QStringList cppfiles = d.entryList(QStringList() << QLatin1String("*.cpp"), QDir::Files);
if (cppfiles.isEmpty()) {
QStringList files = d.entryList(QStringList() << QLatin1String("*.qml"),
QDir::Files);
foreach (const QString &file, files) {
if (file.at(0).isLower()) {
rv << d.absoluteFilePath(file);
}
}
}
QStringList dirs = d.entryList(QDir::Dirs | QDir::NoDotAndDotDot |
QDir::NoSymLinks);
foreach (const QString &dir, dirs) {
QDir sub = d;
sub.cd(dir);
rv << findQmlFiles(sub);
}
return rv;
}
/*
This test runs all the examples in the declarative UI source tree and ensures
that they start and exit cleanly.
Examples are any .qml files under the examples/ or demos/ directory that start
with a lower case letter.
*/
void tst_examples::examples_data()
{
QTest::addColumn<QString>("file");
QString examples = QLatin1String(SRCDIR) + "/../../../../demos/declarative/";
QString demos = QLatin1String(SRCDIR) + "/../../../../examples/declarative/";
QString snippets = QLatin1String(SRCDIR) + "/../../../../doc/src/snippets/";
QStringList files;
files << findQmlFiles(QDir(examples));
files << findQmlFiles(QDir(demos));
files << findQmlFiles(QDir(snippets));
foreach (const QString &file, files)
QTest::newRow(qPrintable(file)) << file;
}
static void silentErrorsMsgHandler(QtMsgType, const char *)
{
}
void tst_examples::examples()
{
QFETCH(QString, file);
QDeclarativeViewer viewer;
QtMsgHandler old = qInstallMsgHandler(silentErrorsMsgHandler);
QVERIFY(viewer.open(file));
qInstallMsgHandler(old);
if (viewer.view()->status() == QDeclarativeView::Error)
qWarning() << viewer.view()->errors();
QCOMPARE(viewer.view()->status(), QDeclarativeView::Ready);
viewer.show();
QTest::qWaitForWindowShown(&viewer);
}
void tst_examples::sgexamples_data()
{
examples_data();
}
void tst_examples::sgexamples()
{
qputenv("QMLSCENE_IMPORT_NAME", "quick1");
QFETCH(QString, file);
QSGView view;
QtMsgHandler old = qInstallMsgHandler(silentErrorsMsgHandler);
view.setSource(file);
qInstallMsgHandler(old);
if (view.status() == QSGView::Error)
qWarning() << view.errors();
QCOMPARE(view.status(), QSGView::Ready);
view.show();
QTest::qWaitForWindowShown(&view);
}
QTEST_MAIN(tst_examples)
#include "tst_examples.moc"
<|endoftext|> |
<commit_before>
#include <random>
#include <ncurses.h>
#include <string.h>
#include <vector>
#include "maze.h"
#include "menu.h"
#include "windows.h"
using namespace std;
// forward declarations
void get_new_dims(int& nrows, int& ncols, int count);
game_state game_ui(WINDOW *menu_win, game_state state);
game_state game_ui_medium(WINDOW *menu_win);
void success_splash(WINDOW *win, int count);
void content_screen(WINDOW *win, string txt);
// constants for splash screen
const char* splash_exclaim[] = {"", "Success! ", "Finally! ", "Whew! "};
const int n_splash_exclaim = sizeof(splash_exclaim) / sizeof(char *);
const char* splash_success[] = {"You did it!",
"You solved it!",
"You solved the maze!",
"You found a way out!",
"You are through the maze!",
"You found your way through the maze!",
"You are through!"
"You found the end of the laybrinth!",};
const int n_splash_success = sizeof(splash_success) / sizeof(char *);
// TODO: Add more of these
const char* splash_story[] = {"You delve deeper.",
"You kick over a dusty old pile of Orcish remains that block the staircase.",
"You take a short rest before taking the staircase down.",
"At the end of the maze you find a staircase leading down.",
"You find a staircase leading down and follow it.",
"Deeper and deeper into the Halls of the Mountain King...",
"Your torch flickers in a draft as you head down the stairs.",
"You hear the echoes of war drums far off in the distance.",
"You find a curving ramp leading further down into the mountain.",
"You find a narrow staircase leading down into the mountain.",
"How deep under the mountain does these tunnels go?",
"Above the stone doorway you find an engraved scene of a human archer killing a dragon.",
"Engraved along the walls of the spiral staircase are scenes of a dwarf being buried with a glowing gem."};
const int n_splash_story = sizeof(splash_story) / sizeof(char *);
const char* intro = "You are a young dwarf in the late fourth age of this world.\n\n"
"The number of dwarves in the world has dwindles and foul creatures have "
"taken over your home Erebor, the Lonely Mountain. You are too late to "
"save your people, but deep under the mountain, in the labyrnths and "
"catacombs a weapon is buried that is said can destroy the "
"Lonely Mountain.\n\nThe last thing you want is to destroy your homeland, "
"but the hoards in the mountain grow strong and you can't let them "
"survive to attack Middle Earth.\n\nSo you head into the catacombs with "
"no thought over ever getting out."; // TODO: "weapon is" overruns a line
/**
* The basic maze GUI.
*
* Use arrow keys to navigate the maze or type "q" to quit.
*/
game_state game_ui(WINDOW *win, game_state state)
{
maze_data maze;
int player[2] = {1, 1};
int count(0);
int c;
int win_y(15);
int win_x(15);
int last_win_y, last_win_x;
// init window at current resolution
content_screen(win, intro);
init_maze_window(win);
getmaxyx(stdscr, win_y, win_x);
last_win_y = win_y;
last_win_x = win_x;
// generate a new maze
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
while (true) {
if (state == game_easy) {
maze_print_easy(win, maze, player);
} else if (state == game_hard) {
maze_print_hard(win, maze, player);
}
// input and update
// TODO: Am I wasting a LOT of cycles here?
c = wgetch(win);
switch (c) {
case KEY_UP:
if (maze_valid_move(maze, player[0] - 1, player[1])) {
player[0] -= 1;
}
break;
case KEY_DOWN:
if (maze_valid_move(maze, player[0] + 1, player[1])) {
player[0] += 1;
}
break;
case KEY_LEFT:
if (maze_valid_move(maze, player[0], player[1] - 1)) {
player[1] -= 1;
}
break;
case KEY_RIGHT:
if (maze_valid_move(maze, player[0], player[1] + 1)) {
player[1] += 1;
}
break;
case 113: // q
return menu_main;
case KEY_RESIZE:
getmaxyx(stdscr, win_y, win_x);
if (last_win_x != win_x || last_win_y != win_y) {
last_win_y = win_y;
last_win_x = win_x;
wresize(win, win_y, win_x);
wclear(win);
box(win, 0, 0);
refresh();
wrefresh(win);
}
break;
// no default actions to be taken
}
// If you reach the end, start over in a new maze
if (player[0] == maze.finish[0] && player[1] == maze.finish[1]) {
success_splash(win, count + 2);
wclear(win);
clear();
box(win, 0, 0);
refresh();
wrefresh(win);
get_new_dims(maze.nrows, maze.ncols, count);
// generate a new maze
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
count += 1;
}
}
}
/**
* The basic maze GUI.
*
* Use arrow keys to navigate the maze or type "q" to quit.
*/
game_state game_ui_medium(WINDOW *win)
{
maze_data maze;
bool visited[maze.max_size * maze.max_size / 2];
int player[2] = {1, 1};
int count(0);
int c;
int win_y(15);
int win_x(15);
int last_win_y, last_win_x;
// init window at current resolution
content_screen(win, intro);
init_maze_window(win);
getmaxyx(stdscr, win_y, win_x);
last_win_y = win_y;
last_win_x = win_x;
// generate a new maze
std::fill_n(visited, maze.max_size * maze.max_size / 2, false);
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
while (true) {
visited[player[0] * maze.max_size + player[1]] = true;
visited[maze.finish[0] * maze.max_size + maze.finish[1]] = true;
maze_print_medium(win, maze, visited, player);
// input and update
c = wgetch(win);
switch (c) {
case KEY_UP:
if (maze_valid_move(maze, player[0] - 1, player[1])) {
player[0] -= 1;
}
break;
case KEY_DOWN:
if (maze_valid_move(maze, player[0] + 1, player[1])) {
player[0] += 1;
}
break;
case KEY_LEFT:
if (maze_valid_move(maze, player[0], player[1] - 1)) {
player[1] -= 1;
}
break;
case KEY_RIGHT:
if (maze_valid_move(maze, player[0], player[1] + 1)) {
player[1] += 1;
}
break;
case 113: // q
return menu_main;
case KEY_RESIZE:
getmaxyx(stdscr, win_y, win_x);
if (last_win_x != win_x || last_win_y != win_y) {
last_win_y = win_y;
last_win_x = win_x;
wresize(win, win_y, win_x);
wclear(win);
box(win, 0, 0);
refresh();
wrefresh(win);
}
break;
// no default actions to be taken
}
// if you reach the end, start over in a new maze
if (player[0] == maze.finish[0] && player[1] == maze.finish[1]) {
success_splash(win, count + 2);
wclear(win);
clear();
box(win, 0, 0);
refresh();
wrefresh(win);
get_new_dims(maze.nrows, maze.ncols, count);
// generate a new maze
std::fill_n(visited, maze.max_size * maze.max_size / 2, false);
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
count += 1;
}
}
}
/**
* Randomly generate maze dimensions.
*/
void get_new_dims(int& nrows, int& ncols, int count) {
count %= 20;
const int bottom_y = 15;
nrows = bottom_y + count / 2 + (rand() % (int)(count / 2 + 1));
if (nrows % 2 == 0) { nrows += 1; }
const int bottom_x = 31;
ncols = bottom_x + count + (rand() % (int)((count) + 1));
if (ncols % 2 == 0) { ncols += 1; }
}
/**
* Format potentially long text for print-out.
*/
vector<string> format_text(const string txt, unsigned int num_cols) {
vector<string> lines;
unsigned int i(0);
unsigned int last_space(0);
unsigned int last_end(0);
// if the line is short, skip all this work
if (txt.length() < num_cols) {
lines.push_back(txt.substr(0));
return lines;
}
// loop through each character
while (i < txt.length()) {
// note the spaces, for clean line breaks
if (txt.at(i) == ' '){
last_space = i;
}
// break on EOL and when you are past the column count
if (txt.at(i) == '\n') {
lines.push_back(txt.substr(last_end, i - last_end));
last_end = i + 1;
} else if ((i - last_end) == num_cols) {
if (last_end >= last_space) {
lines.push_back(txt.substr(last_end, num_cols));
last_end += num_cols;
} else {
lines.push_back(txt.substr(last_end, last_space - last_end));
last_end = last_space + 1;
}
}
i += 1;
}
// add last part of string
lines.push_back(txt.substr(last_end));
return lines;
}
/**
* Splash screen, after you finish a maze
*/
void success_splash(WINDOW *win, int count) {
string txt(string(splash_exclaim[rand() % n_splash_exclaim]) +
string(splash_success[rand() % n_splash_success]) + "\n\n" +
splash_story[rand() % n_splash_story] + "\n\n\n" +
string("You are now ") + to_string(count) + string(" levels under Erebor."));
content_screen(win, txt);
}
/**
* Default function to display text content
*/
void content_screen(WINDOW *win, string txt) {
int win_y(15);
int win_x(15);
mvwin(win, 0, 0);
getmaxyx(stdscr, win_y, win_x);
wresize(win, win_y, win_x);
wclear(win);
box(win, 0, 0);
if (win_y < 6 || win_x < 12) {return;}
unsigned int num_rows(win_y - 2);
int num_cols(win_x - 4);
vector<string> lines(format_text(txt, num_cols));
unsigned int row(1);
for (int i=0; i < (int)lines.size(); ++i) {
mvprintw(row, 2, lines[i].c_str()); // TODO: Should probably be a vector of const char*
row += 1;
if (row == num_rows) {
row = 0;
wrefresh(win);
getch();
wclear(win);
box(win, 0, 0);
}
}
wrefresh(win);
getch();
}
<commit_msg>improving intro text<commit_after>
#include <random>
#include <ncurses.h>
#include <string.h>
#include <vector>
#include "maze.h"
#include "menu.h"
#include "windows.h"
using namespace std;
// forward declarations
void get_new_dims(int& nrows, int& ncols, int count);
game_state game_ui(WINDOW *menu_win, game_state state);
game_state game_ui_medium(WINDOW *menu_win);
void success_splash(WINDOW *win, int count);
void content_screen(WINDOW *win, string txt);
// constants for splash screen
const char* splash_exclaim[] = {"", "Success! ", "Finally! ", "Whew! "};
const int n_splash_exclaim = sizeof(splash_exclaim) / sizeof(char *);
const char* splash_success[] = {"You did it!",
"You solved it!",
"You solved the maze!",
"You found a way out!",
"You are through the maze!",
"You found your way through the maze!",
"You are through!"
"You found the end of the laybrinth!",};
const int n_splash_success = sizeof(splash_success) / sizeof(char *);
// TODO: Add more of these
const char* splash_story[] = {"You delve deeper.",
"You kick over a dusty old pile of Orcish remains that block the staircase.",
"You take a short rest before taking the staircase down.",
"At the end of the maze you find a staircase leading down.",
"You find a staircase leading down and follow it.",
"Deeper and deeper into the Halls of the Mountain King...",
"Your torch flickers in a draft as you head down the stairs.",
"You hear the echoes of war drums far off in the distance.",
"You find a curving ramp leading further down into the mountain.",
"You find a narrow staircase leading down into the mountain.",
"How deep under the mountain does these tunnels go?",
"Above the stone doorway you find an engraved scene of a human archer killing a dragon.",
"Engraved along the walls of the spiral staircase are scenes of a dwarf being buried with a glowing gem."};
const int n_splash_story = sizeof(splash_story) / sizeof(char *);
const char* intro = "You are a young dwarf in the late fourth age of this world.\n\n"
"You are Florin, son of Gimli and Roger, and you can feel that the fourth "
"age of the world is drawing to a close. You hail from the the great "
"northern city of Annúminas, which your Dwarven ancestors helped rebuild."
"\n\nThere are very few Dwarves left in the world. Erebor, their last "
"great citadel, fell to a goblin army many centuries ago. There simply "
"weren't enough Dwarves left to defend the Lonely Mountain. Your father, "
"a great stone mason, was with the last human army to try and assault the "
"mountain. Their losses were terrible, and they never got passed the gate. "
"Instead, they walled up the gate and left the goblin army to starve in the "
"mines.\n\nIt has been 200 years since that battle and the humans have long "
"since forgot the threat. The young kings cannot believe that anyone could "
"long survive under ground. But they do not know the ways of Dwarven mining. "
"They do not know about black moth honey or grassing blind, pale livestock "
"on the deep moss that grows along the shores of underground lakes and "
"streams. And the goblin rabble always preferred living underground. They "
"could tunnel out in a few short weeks, if they wanted.\n\nWord has reached "
"your ear, though, that the last elven queen foretold of huge armies "
"underneath the Lonely Mountain. Whose numbers are now nearly large enough "
"to assault Middle Earth and win. You have decided to defend the world by "
"venturing deep underneath the Lonely Mountain. Far under the labyrinths and "
"catacombs there lies a single weapon that the elven queen said could bring "
"down the mountain. It will collapse deep into the Earth, lava will consume "
"it, and every goblin it it will parish.\n\nDelving into the mountain would "
"mean facing the goblin hoards alone. Along with whatever fel beasts they "
"have bred. If you succeed, you will destroy the final home of Dwarves in "
"Middle Earth. And you will be deep under the mountain when it falls. But "
"you are half human, and cannot let the world fall without defending it.\n\n"
"You set off quietly months ago and started mining out the hidden entrance "
"your father left to the undermines. Sealing yourself in as you go. Today "
"you break through and enter the catacombs for the first and last time."
/**
* The basic maze GUI.
*
* Use arrow keys to navigate the maze or type "q" to quit.
*/
game_state game_ui(WINDOW *win, game_state state)
{
maze_data maze;
int player[2] = {1, 1};
int count(0);
int c;
int win_y(15);
int win_x(15);
int last_win_y, last_win_x;
// init window at current resolution
content_screen(win, intro);
init_maze_window(win);
getmaxyx(stdscr, win_y, win_x);
last_win_y = win_y;
last_win_x = win_x;
// generate a new maze
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
while (true) {
if (state == game_easy) {
maze_print_easy(win, maze, player);
} else if (state == game_hard) {
maze_print_hard(win, maze, player);
}
// input and update
// TODO: Am I wasting a LOT of cycles here?
c = wgetch(win);
switch (c) {
case KEY_UP:
if (maze_valid_move(maze, player[0] - 1, player[1])) {
player[0] -= 1;
}
break;
case KEY_DOWN:
if (maze_valid_move(maze, player[0] + 1, player[1])) {
player[0] += 1;
}
break;
case KEY_LEFT:
if (maze_valid_move(maze, player[0], player[1] - 1)) {
player[1] -= 1;
}
break;
case KEY_RIGHT:
if (maze_valid_move(maze, player[0], player[1] + 1)) {
player[1] += 1;
}
break;
case 113: // q
return menu_main;
case KEY_RESIZE:
getmaxyx(stdscr, win_y, win_x);
if (last_win_x != win_x || last_win_y != win_y) {
last_win_y = win_y;
last_win_x = win_x;
wresize(win, win_y, win_x);
wclear(win);
box(win, 0, 0);
refresh();
wrefresh(win);
}
break;
// no default actions to be taken
}
// If you reach the end, start over in a new maze
if (player[0] == maze.finish[0] && player[1] == maze.finish[1]) {
success_splash(win, count + 2);
wclear(win);
clear();
box(win, 0, 0);
refresh();
wrefresh(win);
get_new_dims(maze.nrows, maze.ncols, count);
// generate a new maze
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
count += 1;
}
}
}
/**
* The basic maze GUI.
*
* Use arrow keys to navigate the maze or type "q" to quit.
*/
game_state game_ui_medium(WINDOW *win)
{
maze_data maze;
bool visited[maze.max_size * maze.max_size / 2];
int player[2] = {1, 1};
int count(0);
int c;
int win_y(15);
int win_x(15);
int last_win_y, last_win_x;
// init window at current resolution
content_screen(win, intro);
init_maze_window(win);
getmaxyx(stdscr, win_y, win_x);
last_win_y = win_y;
last_win_x = win_x;
// generate a new maze
std::fill_n(visited, maze.max_size * maze.max_size / 2, false);
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
while (true) {
visited[player[0] * maze.max_size + player[1]] = true;
visited[maze.finish[0] * maze.max_size + maze.finish[1]] = true;
maze_print_medium(win, maze, visited, player);
// input and update
c = wgetch(win);
switch (c) {
case KEY_UP:
if (maze_valid_move(maze, player[0] - 1, player[1])) {
player[0] -= 1;
}
break;
case KEY_DOWN:
if (maze_valid_move(maze, player[0] + 1, player[1])) {
player[0] += 1;
}
break;
case KEY_LEFT:
if (maze_valid_move(maze, player[0], player[1] - 1)) {
player[1] -= 1;
}
break;
case KEY_RIGHT:
if (maze_valid_move(maze, player[0], player[1] + 1)) {
player[1] += 1;
}
break;
case 113: // q
return menu_main;
case KEY_RESIZE:
getmaxyx(stdscr, win_y, win_x);
if (last_win_x != win_x || last_win_y != win_y) {
last_win_y = win_y;
last_win_x = win_x;
wresize(win, win_y, win_x);
wclear(win);
box(win, 0, 0);
refresh();
wrefresh(win);
}
break;
// no default actions to be taken
}
// if you reach the end, start over in a new maze
if (player[0] == maze.finish[0] && player[1] == maze.finish[1]) {
success_splash(win, count + 2);
wclear(win);
clear();
box(win, 0, 0);
refresh();
wrefresh(win);
get_new_dims(maze.nrows, maze.ncols, count);
// generate a new maze
std::fill_n(visited, maze.max_size * maze.max_size / 2, false);
backtracking_maze_gen(&maze);
gen_entrances_opposites(&maze);
player[0] = maze.start[0];
player[1] = maze.start[1];
count += 1;
}
}
}
/**
* Randomly generate maze dimensions.
*/
void get_new_dims(int& nrows, int& ncols, int count) {
count %= 20;
const int bottom_y = 15;
nrows = bottom_y + count / 2 + (rand() % (int)(count / 2 + 1));
if (nrows % 2 == 0) { nrows += 1; }
const int bottom_x = 31;
ncols = bottom_x + count + (rand() % (int)((count) + 1));
if (ncols % 2 == 0) { ncols += 1; }
}
/**
* Format potentially long text for print-out.
*/
vector<string> format_text(const string txt, unsigned int num_cols) {
vector<string> lines;
unsigned int i(0);
unsigned int last_space(0);
unsigned int last_end(0);
// if the line is short, skip all this work
if (txt.length() < num_cols) {
lines.push_back(txt.substr(0));
return lines;
}
// loop through each character
while (i < txt.length()) {
// note the spaces, for clean line breaks
if (txt.at(i) == ' '){
last_space = i;
}
// break on EOL and when you are past the column count
if (txt.at(i) == '\n') {
lines.push_back(txt.substr(last_end, i - last_end));
last_end = i + 1;
} else if ((i - last_end) == num_cols) {
if (last_end >= last_space) {
lines.push_back(txt.substr(last_end, num_cols));
last_end += num_cols;
} else {
lines.push_back(txt.substr(last_end, last_space - last_end));
last_end = last_space + 1;
}
}
i += 1;
}
// add last part of string
lines.push_back(txt.substr(last_end));
return lines;
}
/**
* Splash screen, after you finish a maze
*/
void success_splash(WINDOW *win, int count) {
string txt(string(splash_exclaim[rand() % n_splash_exclaim]) +
string(splash_success[rand() % n_splash_success]) + "\n\n" +
splash_story[rand() % n_splash_story] + "\n\n\n" +
string("You are now ") + to_string(count) + string(" levels under Erebor."));
content_screen(win, txt);
}
/**
* Default function to display text content
*/
void content_screen(WINDOW *win, string txt) {
int win_y(15);
int win_x(15);
mvwin(win, 0, 0);
getmaxyx(stdscr, win_y, win_x);
wresize(win, win_y, win_x);
wclear(win);
box(win, 0, 0);
if (win_y < 6 || win_x < 12) {return;}
unsigned int num_rows(win_y - 2);
int num_cols(win_x - 4);
vector<string> lines(format_text(txt, num_cols));
unsigned int row(1);
for (int i=0; i < (int)lines.size(); ++i) {
mvprintw(row, 2, lines[i].c_str()); // TODO: Should probably be a vector of const char*
row += 1;
if (row == num_rows) {
row = 0;
wrefresh(win);
getch();
wclear(win);
box(win, 0, 0);
}
}
wrefresh(win);
getch();
}
<|endoftext|> |
<commit_before>/*
* Copyright (C) 2010-2014 Jeremy Lainé
* Contact: https://github.com/jlaine/qdjango
*
* This file is part of the QDjango Library.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*/
#include <QSqlDriver>
#include "QDjango.h"
#include "QDjangoQuerySet.h"
#include "QDjangoWhere.h"
#include "util.h"
class Item : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
public:
Item(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
private:
QString m_name;
};
class Owner : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(Item* item1 READ item1 WRITE setItem1)
Q_PROPERTY(Item* item2 READ item2 WRITE setItem2)
public:
Owner(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
Item *item1() const;
void setItem1(Item *item1);
Item *item2() const;
void setItem2(Item *item2);
private:
QString m_name;
};
class OwnerWithNullableItem : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(Item* item1 READ item1 WRITE setItem1)
Q_PROPERTY(Item* item2 READ item2 WRITE setItem2)
Q_CLASSINFO("item2", "null=true")
public:
OwnerWithNullableItem(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
Item *item1() const;
void setItem1(Item *item1);
Item *item2() const;
void setItem2(Item *item2);
private:
QString m_name;
};
class Top : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(Owner *owner READ owner WRITE setOwner)
public:
Top(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
Owner *owner() const;
void setOwner(Owner *owner);
private:
QString m_name;
};
class TopWithNullableItem : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(OwnerWithNullableItem *owner READ owner WRITE setOwner)
public:
TopWithNullableItem(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
OwnerWithNullableItem *owner() const;
void setOwner(OwnerWithNullableItem *owner);
private:
QString m_name;
};
class tst_QDjangoCompiler : public QObject
{
Q_OBJECT
private slots:
void initTestCase();
void fieldNames_data();
void fieldNames();
void orderLimit_data();
void orderLimit();
void resolve();
};
Item::Item(QObject *parent)
: QDjangoModel(parent)
{
}
QString Item::name() const
{
return m_name;
}
void Item::setName(const QString &name)
{
m_name = name;
}
Owner::Owner(QObject *parent)
: QDjangoModel(parent)
{
setForeignKey("item1", new Item(this));
setForeignKey("item2", new Item(this));
}
QString Owner::name() const
{
return m_name;
}
void Owner::setName(const QString &name)
{
m_name = name;
}
Item* Owner::item1() const
{
return qobject_cast<Item*>(foreignKey("item1"));
}
void Owner::setItem1(Item *item1)
{
setForeignKey("item1", item1);
}
Item* Owner::item2() const
{
return qobject_cast<Item*>(foreignKey("item2"));
}
void Owner::setItem2(Item *item2)
{
setForeignKey("item2", item2);
}
OwnerWithNullableItem::OwnerWithNullableItem(QObject *parent)
: QDjangoModel(parent)
{
setForeignKey("item1", new Item(this));
setForeignKey("item2", new Item(this));
}
QString OwnerWithNullableItem::name() const
{
return m_name;
}
void OwnerWithNullableItem::setName(const QString &name)
{
m_name = name;
}
Item* OwnerWithNullableItem::item1() const
{
return qobject_cast<Item*>(foreignKey("item1"));
}
void OwnerWithNullableItem::setItem1(Item *item1)
{
setForeignKey("item1", item1);
}
Item* OwnerWithNullableItem::item2() const
{
return qobject_cast<Item*>(foreignKey("item2"));
}
void OwnerWithNullableItem::setItem2(Item *item2)
{
setForeignKey("item2", item2);
}
Top::Top(QObject *parent)
: QDjangoModel(parent)
{
}
QString Top::name() const
{
return m_name;
}
void Top::setName(const QString &name)
{
m_name = name;
}
Owner* Top::owner() const
{
return qobject_cast<Owner*>(foreignKey("owner"));
}
void Top::setOwner(Owner *owner)
{
setForeignKey("owner", owner);
}
TopWithNullableItem::TopWithNullableItem(QObject *parent)
: QDjangoModel(parent)
{
}
QString TopWithNullableItem::name() const
{
return m_name;
}
void TopWithNullableItem::setName(const QString &name)
{
m_name = name;
}
OwnerWithNullableItem* TopWithNullableItem::owner() const
{
return qobject_cast<OwnerWithNullableItem*>(foreignKey("owner"));
}
void TopWithNullableItem::setOwner(OwnerWithNullableItem *owner)
{
setForeignKey("owner", owner);
}
void tst_QDjangoCompiler::initTestCase()
{
QVERIFY(initialiseDatabase());
QDjango::registerModel<Item>();
QDjango::registerModel<Owner>();
QDjango::registerModel<OwnerWithNullableItem>();
QDjango::registerModel<Top>();
QDjango::registerModel<TopWithNullableItem>();
}
void tst_QDjangoCompiler::fieldNames_data()
{
QSqlDatabase db = QDjango::database();
QTest::addColumn<QByteArray>("modelName");
QTest::addColumn<bool>("recursive");
QTest::addColumn<QStringList>("fieldNames");
QTest::addColumn<QString>("fromSql");
QTest::newRow("non recursive") << QByteArray("Owner") << false << (QStringList()
<< "\"owner\".\"id\""
<< "\"owner\".\"name\""
<< "\"owner\".\"item1_id\""
<< "\"owner\".\"item2_id\"")
<< "\"owner\"";
QTest::newRow("recurse one level") << QByteArray("Owner") << true << (QStringList()
<< "\"owner\".\"id\""
<< "\"owner\".\"name\""
<< "\"owner\".\"item1_id\""
<< "\"owner\".\"item2_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T1.\"id\""
<< "T1.\"name\"")
<< "\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = \"owner\".\"item2_id\"";
QTest::newRow("recurse with nullable") << QByteArray("OwnerWithNullableItem") << true << (QStringList()
<< "\"ownerwithnullableitem\".\"id\""
<< "\"ownerwithnullableitem\".\"name\""
<< "\"ownerwithnullableitem\".\"item1_id\""
<< "\"ownerwithnullableitem\".\"item2_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T1.\"id\""
<< "T1.\"name\"")
<< "\"ownerwithnullableitem\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"ownerwithnullableitem\".\"item1_id\""
" LEFT OUTER JOIN \"item\" T1 ON T1.\"id\" = \"ownerwithnullableitem\".\"item2_id\"";
QTest::newRow("recurse two levels") << QByteArray("Top") << true << (QStringList()
<< "\"top\".\"id\""
<< "\"top\".\"name\""
<< "\"top\".\"owner_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T0.\"item1_id\""
<< "T0.\"item2_id\""
<< "T1.\"id\""
<< "T1.\"name\""
<< "T2.\"id\""
<< "T2.\"name\"")
<< "\"top\""
" INNER JOIN \"owner\" T0 ON T0.\"id\" = \"top\".\"owner_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = T0.\"item1_id\""
" INNER JOIN \"item\" T2 ON T2.\"id\" = T0.\"item2_id\"";
QTest::newRow("recurse two levels with nullable item") << QByteArray("TopWithNullableItem") << true << (QStringList()
<< "\"topwithnullableitem\".\"id\""
<< "\"topwithnullableitem\".\"name\""
<< "\"topwithnullableitem\".\"owner_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T0.\"item1_id\""
<< "T0.\"item2_id\""
<< "T1.\"id\""
<< "T1.\"name\""
<< "T2.\"id\""
<< "T2.\"name\"")
<< "\"topwithnullableitem\""
" INNER JOIN \"ownerwithnullableitem\" T0 ON T0.\"id\" = \"topwithnullableitem\".\"owner_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = T0.\"item1_id\""
" LEFT OUTER JOIN \"item\" T2 ON T2.\"id\" = T0.\"item2_id\"";
}
void tst_QDjangoCompiler::fieldNames()
{
QFETCH(QByteArray, modelName);
QFETCH(bool, recursive);
QFETCH(QStringList, fieldNames);
QFETCH(QString, fromSql);
QSqlDatabase db = QDjango::database();
QDjangoCompiler compiler(modelName, db);
QStringList normalizedNames;
QStringList rawNames = compiler.fieldNames(recursive);
foreach (const QString &rawName, rawNames) {
normalizedNames << normalizeSql(db, rawName);
}
QCOMPARE(normalizedNames, fieldNames);
QCOMPARE(normalizeSql(db, compiler.fromSql()), fromSql);
}
void tst_QDjangoCompiler::orderLimit_data()
{
QTest::addColumn<QByteArray>("modelName");
QTest::addColumn<QStringList>("orderBy");
QTest::addColumn<QString>("orderSql");
QTest::addColumn<QString>("fromSql");
QTest::newRow("order ascending") << QByteArray("Owner") << QStringList("name")
<< QString(" ORDER BY \"owner\".\"name\" ASC")
<< QString("\"owner\"");
QTest::newRow("order ascending foreign") << QByteArray("Owner") << QStringList("item1__name")
<< QString(" ORDER BY T0.\"name\" ASC")
<< "\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\"";
QTest::newRow("order ascending foreign double") << QByteArray("Owner") << (QStringList() << "item1__name" << "item2__name")
<< QString(" ORDER BY T0.\"name\" ASC, T1.\"name\" ASC")
<< "\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = \"owner\".\"item2_id\"";
QTest::newRow("order descending") << QByteArray("Owner") << QStringList("-name")
<< QString(" ORDER BY \"owner\".\"name\" DESC")
<< QString("\"owner\"");
}
void tst_QDjangoCompiler::orderLimit()
{
QSqlDatabase db = QDjango::database();
QFETCH(QByteArray, modelName);
QFETCH(QStringList, orderBy);
QFETCH(QString, orderSql);
QFETCH(QString, fromSql);
QDjangoCompiler compiler(modelName, db);
QCOMPARE(normalizeSql(db, compiler.orderLimitSql(orderBy, 0, 0)), orderSql);
QCOMPARE(normalizeSql(db, compiler.fromSql()), fromSql);
}
void tst_QDjangoCompiler::resolve()
{
QSqlDatabase db = QDjango::database();
QDjangoCompiler compiler("Owner", db);
QDjangoWhere where("name", QDjangoWhere::Equals, "foo");
compiler.resolve(where);
CHECKWHERE(where, QLatin1String("\"owner\".\"name\" = ?"), QVariantList() << "foo");
QCOMPARE(normalizeSql(db, compiler.fromSql()), QString("\"owner\""));
compiler = QDjangoCompiler("Owner", db);
where = QDjangoWhere("item1__name", QDjangoWhere::Equals, "foo");
compiler.resolve(where);
CHECKWHERE(where, QLatin1String("T0.\"name\" = ?"), QVariantList() << "foo");
QCOMPARE(normalizeSql(db, compiler.fromSql()), QString("\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""));
compiler = QDjangoCompiler("Owner", db);
where = QDjangoWhere("item1__name", QDjangoWhere::Equals, "foo")
&& QDjangoWhere("item2__name", QDjangoWhere::Equals, "bar");
compiler.resolve(where);
CHECKWHERE(where, QLatin1String("T0.\"name\" = ? AND T1.\"name\" = ?"), QVariantList() << "foo" << "bar");
QCOMPARE(normalizeSql(db, compiler.fromSql()), QString("\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = \"owner\".\"item2_id\""));
}
QTEST_MAIN(tst_QDjangoCompiler)
#include "tst_qdjangocompiler.moc"
<commit_msg>improve test coverage<commit_after>/*
* Copyright (C) 2010-2014 Jeremy Lainé
* Contact: https://github.com/jlaine/qdjango
*
* This file is part of the QDjango Library.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*/
#include <QSqlDriver>
#include "QDjango.h"
#include "QDjangoQuerySet.h"
#include "QDjangoWhere.h"
#include "util.h"
class Item : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
public:
Item(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
private:
QString m_name;
};
class Owner : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(Item* item1 READ item1 WRITE setItem1)
Q_PROPERTY(Item* item2 READ item2 WRITE setItem2)
public:
Owner(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
Item *item1() const;
void setItem1(Item *item1);
Item *item2() const;
void setItem2(Item *item2);
private:
QString m_name;
};
class OwnerWithNullableItem : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(Item* item1 READ item1 WRITE setItem1)
Q_PROPERTY(Item* item2 READ item2 WRITE setItem2)
Q_CLASSINFO("item2", "null=true")
public:
OwnerWithNullableItem(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
Item *item1() const;
void setItem1(Item *item1);
Item *item2() const;
void setItem2(Item *item2);
private:
QString m_name;
};
class Top : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(Owner *owner READ owner WRITE setOwner)
public:
Top(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
Owner *owner() const;
void setOwner(Owner *owner);
private:
QString m_name;
};
class TopWithNullableItem : public QDjangoModel
{
Q_OBJECT
Q_PROPERTY(QString name READ name WRITE setName)
Q_PROPERTY(OwnerWithNullableItem *owner READ owner WRITE setOwner)
public:
TopWithNullableItem(QObject *parent = 0);
QString name() const;
void setName(const QString &name);
OwnerWithNullableItem *owner() const;
void setOwner(OwnerWithNullableItem *owner);
private:
QString m_name;
};
class tst_QDjangoCompiler : public QObject
{
Q_OBJECT
private slots:
void initTestCase();
void fieldNames_data();
void fieldNames();
void orderLimit_data();
void orderLimit();
void resolve();
};
Item::Item(QObject *parent)
: QDjangoModel(parent)
{
}
QString Item::name() const
{
return m_name;
}
void Item::setName(const QString &name)
{
m_name = name;
}
Owner::Owner(QObject *parent)
: QDjangoModel(parent)
{
setForeignKey("item1", new Item(this));
setForeignKey("item2", new Item(this));
}
QString Owner::name() const
{
return m_name;
}
void Owner::setName(const QString &name)
{
m_name = name;
}
Item* Owner::item1() const
{
return qobject_cast<Item*>(foreignKey("item1"));
}
void Owner::setItem1(Item *item1)
{
setForeignKey("item1", item1);
}
Item* Owner::item2() const
{
return qobject_cast<Item*>(foreignKey("item2"));
}
void Owner::setItem2(Item *item2)
{
setForeignKey("item2", item2);
}
OwnerWithNullableItem::OwnerWithNullableItem(QObject *parent)
: QDjangoModel(parent)
{
setForeignKey("item1", new Item(this));
setForeignKey("item2", new Item(this));
}
QString OwnerWithNullableItem::name() const
{
return m_name;
}
void OwnerWithNullableItem::setName(const QString &name)
{
m_name = name;
}
Item* OwnerWithNullableItem::item1() const
{
return qobject_cast<Item*>(foreignKey("item1"));
}
void OwnerWithNullableItem::setItem1(Item *item1)
{
setForeignKey("item1", item1);
}
Item* OwnerWithNullableItem::item2() const
{
return qobject_cast<Item*>(foreignKey("item2"));
}
void OwnerWithNullableItem::setItem2(Item *item2)
{
setForeignKey("item2", item2);
}
Top::Top(QObject *parent)
: QDjangoModel(parent)
{
}
QString Top::name() const
{
return m_name;
}
void Top::setName(const QString &name)
{
m_name = name;
}
Owner* Top::owner() const
{
return qobject_cast<Owner*>(foreignKey("owner"));
}
void Top::setOwner(Owner *owner)
{
setForeignKey("owner", owner);
}
TopWithNullableItem::TopWithNullableItem(QObject *parent)
: QDjangoModel(parent)
{
}
QString TopWithNullableItem::name() const
{
return m_name;
}
void TopWithNullableItem::setName(const QString &name)
{
m_name = name;
}
OwnerWithNullableItem* TopWithNullableItem::owner() const
{
return qobject_cast<OwnerWithNullableItem*>(foreignKey("owner"));
}
void TopWithNullableItem::setOwner(OwnerWithNullableItem *owner)
{
setForeignKey("owner", owner);
}
void tst_QDjangoCompiler::initTestCase()
{
QVERIFY(initialiseDatabase());
QDjango::registerModel<Item>();
QDjango::registerModel<Owner>();
QDjango::registerModel<OwnerWithNullableItem>();
QDjango::registerModel<Top>();
QDjango::registerModel<TopWithNullableItem>();
}
void tst_QDjangoCompiler::fieldNames_data()
{
QSqlDatabase db = QDjango::database();
QTest::addColumn<QByteArray>("modelName");
QTest::addColumn<bool>("recursive");
QTest::addColumn<QStringList>("fieldNames");
QTest::addColumn<QString>("fromSql");
QTest::newRow("non recursive") << QByteArray("Owner") << false << (QStringList()
<< "\"owner\".\"id\""
<< "\"owner\".\"name\""
<< "\"owner\".\"item1_id\""
<< "\"owner\".\"item2_id\"")
<< "\"owner\"";
QTest::newRow("recurse one level") << QByteArray("Owner") << true << (QStringList()
<< "\"owner\".\"id\""
<< "\"owner\".\"name\""
<< "\"owner\".\"item1_id\""
<< "\"owner\".\"item2_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T1.\"id\""
<< "T1.\"name\"")
<< "\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = \"owner\".\"item2_id\"";
QTest::newRow("recurse with nullable") << QByteArray("OwnerWithNullableItem") << true << (QStringList()
<< "\"ownerwithnullableitem\".\"id\""
<< "\"ownerwithnullableitem\".\"name\""
<< "\"ownerwithnullableitem\".\"item1_id\""
<< "\"ownerwithnullableitem\".\"item2_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T1.\"id\""
<< "T1.\"name\"")
<< "\"ownerwithnullableitem\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"ownerwithnullableitem\".\"item1_id\""
" LEFT OUTER JOIN \"item\" T1 ON T1.\"id\" = \"ownerwithnullableitem\".\"item2_id\"";
QTest::newRow("recurse two levels") << QByteArray("Top") << true << (QStringList()
<< "\"top\".\"id\""
<< "\"top\".\"name\""
<< "\"top\".\"owner_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T0.\"item1_id\""
<< "T0.\"item2_id\""
<< "T1.\"id\""
<< "T1.\"name\""
<< "T2.\"id\""
<< "T2.\"name\"")
<< "\"top\""
" INNER JOIN \"owner\" T0 ON T0.\"id\" = \"top\".\"owner_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = T0.\"item1_id\""
" INNER JOIN \"item\" T2 ON T2.\"id\" = T0.\"item2_id\"";
QTest::newRow("recurse two levels with nullable item") << QByteArray("TopWithNullableItem") << true << (QStringList()
<< "\"topwithnullableitem\".\"id\""
<< "\"topwithnullableitem\".\"name\""
<< "\"topwithnullableitem\".\"owner_id\""
<< "T0.\"id\""
<< "T0.\"name\""
<< "T0.\"item1_id\""
<< "T0.\"item2_id\""
<< "T1.\"id\""
<< "T1.\"name\""
<< "T2.\"id\""
<< "T2.\"name\"")
<< "\"topwithnullableitem\""
" INNER JOIN \"ownerwithnullableitem\" T0 ON T0.\"id\" = \"topwithnullableitem\".\"owner_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = T0.\"item1_id\""
" LEFT OUTER JOIN \"item\" T2 ON T2.\"id\" = T0.\"item2_id\"";
}
void tst_QDjangoCompiler::fieldNames()
{
QFETCH(QByteArray, modelName);
QFETCH(bool, recursive);
QFETCH(QStringList, fieldNames);
QFETCH(QString, fromSql);
QSqlDatabase db = QDjango::database();
QDjangoCompiler compiler(modelName, db);
QStringList normalizedNames;
QStringList rawNames = compiler.fieldNames(recursive);
foreach (const QString &rawName, rawNames) {
normalizedNames << normalizeSql(db, rawName);
}
QCOMPARE(normalizedNames, fieldNames);
QCOMPARE(normalizeSql(db, compiler.fromSql()), fromSql);
}
void tst_QDjangoCompiler::orderLimit_data()
{
QTest::addColumn<QByteArray>("modelName");
QTest::addColumn<QStringList>("orderBy");
QTest::addColumn<QString>("orderSql");
QTest::addColumn<QString>("fromSql");
QTest::newRow("order ascending") << QByteArray("Owner") << QStringList("name")
<< QString(" ORDER BY \"owner\".\"name\" ASC")
<< QString("\"owner\"");
QTest::newRow("order ascending foreign") << QByteArray("Owner") << QStringList("item1__name")
<< QString(" ORDER BY T0.\"name\" ASC")
<< "\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\"";
QTest::newRow("order ascending foreign double") << QByteArray("Owner") << (QStringList() << "item1__name" << "item2__name")
<< QString(" ORDER BY T0.\"name\" ASC, T1.\"name\" ASC")
<< "\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = \"owner\".\"item2_id\"";
QTest::newRow("order descending") << QByteArray("Owner") << QStringList("-name")
<< QString(" ORDER BY \"owner\".\"name\" DESC")
<< QString("\"owner\"");
}
void tst_QDjangoCompiler::orderLimit()
{
QSqlDatabase db = QDjango::database();
QFETCH(QByteArray, modelName);
QFETCH(QStringList, orderBy);
QFETCH(QString, orderSql);
QFETCH(QString, fromSql);
QDjangoCompiler compiler(modelName, db);
QCOMPARE(normalizeSql(db, compiler.orderLimitSql(orderBy, 0, 0)), orderSql);
QCOMPARE(normalizeSql(db, compiler.fromSql()), fromSql);
}
void tst_QDjangoCompiler::resolve()
{
QSqlDatabase db = QDjango::database();
QDjangoCompiler compiler("Owner", db);
QDjangoWhere where("name", QDjangoWhere::Equals, "foo");
compiler.resolve(where);
CHECKWHERE(where, QLatin1String("\"owner\".\"name\" = ?"), QVariantList() << "foo");
QCOMPARE(normalizeSql(db, compiler.fromSql()), QString("\"owner\""));
compiler = QDjangoCompiler("Owner", db);
where = QDjangoWhere("item1__name", QDjangoWhere::Equals, "foo");
compiler.resolve(where);
CHECKWHERE(where, QLatin1String("T0.\"name\" = ?"), QVariantList() << "foo");
QCOMPARE(normalizeSql(db, compiler.fromSql()), QString("\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""));
compiler = QDjangoCompiler("Owner", db);
where = QDjangoWhere("top__name", QDjangoWhere::Equals, "foo");
compiler.resolve(where);
CHECKWHERE(where, QLatin1String("T0.\"name\" = ?"), QVariantList() << "foo");
QCOMPARE(normalizeSql(db, compiler.fromSql()), QString("\"owner\""
" INNER JOIN \"top\" T0 ON T0.\"owner_id\" = \"owner\".\"id\""));
compiler = QDjangoCompiler("Owner", db);
where = QDjangoWhere("item1__name", QDjangoWhere::Equals, "foo")
&& QDjangoWhere("item2__name", QDjangoWhere::Equals, "bar");
compiler.resolve(where);
CHECKWHERE(where, QLatin1String("T0.\"name\" = ? AND T1.\"name\" = ?"), QVariantList() << "foo" << "bar");
QCOMPARE(normalizeSql(db, compiler.fromSql()), QString("\"owner\""
" INNER JOIN \"item\" T0 ON T0.\"id\" = \"owner\".\"item1_id\""
" INNER JOIN \"item\" T1 ON T1.\"id\" = \"owner\".\"item2_id\""));
}
QTEST_MAIN(tst_QDjangoCompiler)
#include "tst_qdjangocompiler.moc"
<|endoftext|> |
<commit_before>// ======================================================================== //
// Copyright 2009-2017 Intel Corporation //
// //
// Licensed under the Apache License, Version 2.0 (the "License"); //
// you may not use this file except in compliance with the License. //
// You may obtain a copy of the License at //
// //
// http://www.apache.org/licenses/LICENSE-2.0 //
// //
// Unless required by applicable law or agreed to in writing, software //
// distributed under the License is distributed on an "AS IS" BASIS, //
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. //
// See the License for the specific language governing permissions and //
// limitations under the License. //
// ======================================================================== //
#undef NDEBUG // do all assertions in this file
//ospray
#include "ospray/camera/Camera.h"
#include "ospray/common/Data.h"
#include "ospray/lights/Light.h"
#include "ospray/transferFunction/TransferFunction.h"
//mpiCommon
#include "mpiCommon/MPICommon.h"
//ospray_mpi
#include "mpi/MPIDistributedDevice.h"
#include "mpi/fb/DistributedFrameBuffer.h"
#include "mpi/render/MPILoadBalancer.h"
//distributed objects
#include "render/distributed/DistributedRaycast.h"
#ifdef OPEN_MPI
# include <thread>
//# define _GNU_SOURCE
# include <sched.h>
#endif
namespace ospray {
namespace mpi {
// Helper functions ///////////////////////////////////////////////////////
template <typename OSPRAY_TYPE, typename API_TYPE>
inline API_TYPE createOSPRayObjectWithHandle(const char *type)
{
auto *instance = OSPRAY_TYPE::createInstance(type);
instance->refInc();
ObjectHandle handle;
handle.assign(instance);
return (API_TYPE)(int64)handle;
}
template <typename OSPRAY_TYPE>
inline OSPRAY_TYPE& objectFromAPIHandle(OSPObject obj)
{
auto &handle = reinterpret_cast<ObjectHandle&>(obj);
auto *object = (OSPRAY_TYPE*)handle.lookup();
if (!object)
throw std::runtime_error("#dmpi: ObjectHandle doesn't exist!");
return *object;
}
static void embreeErrorFunc(const RTCError code, const char* str)
{
postStatusMsg() << "#osp: embree internal error " << code << " : " << str;
throw std::runtime_error("embree internal error '" +std::string(str)+"'");
}
// MPIDistributedDevice definitions ///////////////////////////////////////
MPIDistributedDevice::~MPIDistributedDevice()
{
try {
MPI_CALL(Finalize());
} catch (...) {
//TODO: anything to do here? try-catch added to silence a warning...
}
}
void MPIDistributedDevice::commit()
{
if (!initialized) {
int _ac = 1;
const char *_av[] = {"ospray_mpi_worker"};
mpicommon::init(&_ac, _av);
std::stringstream embreeConfig;
if (debugMode)
embreeConfig << " threads=1,verbose=2";
else if(numThreads > 0)
embreeConfig << " threads=" << numThreads;
embreeDevice = rtcNewDevice(embreeConfig.str().c_str());
rtcDeviceSetErrorFunction(embreeDevice, embreeErrorFunc);
RTCError erc = rtcDeviceGetError(embreeDevice);
if (erc != RTC_NO_ERROR) {
// why did the error function not get called !?
postStatusMsg() << "#osp:init: embree internal error number " << erc;
assert(erc == RTC_NO_ERROR);
}
initialized = true;
}
Device::commit();
masterRank = getParam1i("masterRank", 0);
std::string mode = getParamString("mode", "distributed");
if (mode == "distributed") {
postStatusMsg() << "#dmpi: device commit() setting mode to " << mode;
} else {
throw std::runtime_error("#dmpi: bad device mode ['" + mode + "]");
}
// TODO: implement 'staticLoadBalancer::Distributed'
//TiledLoadBalancer::instance = make_unique<staticLoadBalancer::Master>();
}
OSPFrameBuffer
MPIDistributedDevice::frameBufferCreate(const vec2i &size,
const OSPFrameBufferFormat mode,
const uint32 channels)
{
const bool hasDepthBuffer = channels & OSP_FB_DEPTH;
const bool hasAccumBuffer = channels & OSP_FB_ACCUM;
const bool hasVarianceBuffer = channels & OSP_FB_VARIANCE;
ObjectHandle handle;
auto *instance = new DistributedFrameBuffer(size, handle, mode,
hasDepthBuffer,
hasAccumBuffer,
hasVarianceBuffer,
true);
instance->refInc();
handle.assign(instance);
return (OSPFrameBuffer)(int64)handle;
}
const void*
MPIDistributedDevice::frameBufferMap(OSPFrameBuffer _fb,
OSPFrameBufferChannel channel)
{
if (!mpicommon::IamTheMaster())
throw std::runtime_error("Can only map framebuffer on the master!");
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
switch (channel) {
case OSP_FB_COLOR: return fb.mapColorBuffer();
case OSP_FB_DEPTH: return fb.mapDepthBuffer();
default: return nullptr;
}
}
void MPIDistributedDevice::frameBufferUnmap(const void *mapped,
OSPFrameBuffer _fb)
{
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
fb.unmap(mapped);
}
void MPIDistributedDevice::frameBufferClear(OSPFrameBuffer _fb,
const uint32 fbChannelFlags)
{
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
fb.clear(fbChannelFlags);
}
OSPModel MPIDistributedDevice::newModel()
{
auto *instance = new Model;
instance->refInc();
ObjectHandle handle;
handle.assign(instance);
return (OSPModel)(int64)handle;
}
void MPIDistributedDevice::commit(OSPObject _object)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.commit();
}
void MPIDistributedDevice::addGeometry(OSPModel _model,
OSPGeometry _geometry)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &geom = objectFromAPIHandle<Geometry>(_geometry);
model.geometry.push_back(&geom);
}
void MPIDistributedDevice::addVolume(OSPModel _model, OSPVolume _volume)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &volume = objectFromAPIHandle<Volume>(_volume);
model.volume.push_back(&volume);
}
OSPData MPIDistributedDevice::newData(size_t nitems, OSPDataType format,
void *init, int flags)
{
ObjectHandle handle;
auto *instance = new Data(nitems, format, init, flags);
instance->refInc();
handle.assign(instance);
return (OSPData)(int64)handle;
}
void MPIDistributedDevice::setVoidPtr(OSPObject _object,
const char *bufName,
void *v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::removeParam(OSPObject _object, const char *name)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.removeParam(name);
}
int MPIDistributedDevice::setRegion(OSPVolume _volume, const void *source,
const vec3i &index, const vec3i &count)
{
auto &volume = objectFromAPIHandle<Volume>(_volume);
volume.setRegion(source, index, count);
}
void MPIDistributedDevice::setString(OSPObject _object,
const char *bufName,
const char *s)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(s);
}
int MPIDistributedDevice::loadModule(const char *name)
{
return loadLocalModule(name);
}
void MPIDistributedDevice::setFloat(OSPObject _object,
const char *bufName,
const float f)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(f);
}
void MPIDistributedDevice::setInt(OSPObject _object,
const char *bufName,
const int i)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(i);
}
void MPIDistributedDevice::setVec2f(OSPObject _object,
const char *bufName,
const vec2f &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec3f(OSPObject _object,
const char *bufName,
const vec3f &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec4f(OSPObject _object,
const char *bufName,
const vec4f &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec2i(OSPObject _object,
const char *bufName,
const vec2i &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec3i(OSPObject _object,
const char *bufName,
const vec3i &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setObject(OSPObject _object,
const char *bufName,
OSPObject _value)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
auto &value = objectFromAPIHandle<ManagedObject>(_value);
object.set(bufName, &value);
}
OSPPixelOp MPIDistributedDevice::newPixelOp(const char *type)
{
NOT_IMPLEMENTED;
}
void MPIDistributedDevice::setPixelOp(OSPFrameBuffer _fb, OSPPixelOp _op)
{
NOT_IMPLEMENTED;
}
OSPRenderer MPIDistributedDevice::newRenderer(const char *type)
{
UNUSED(type);
auto *instance = new DistributedRaycastRenderer;
ObjectHandle handle;
handle.assign(instance);
return (OSPRenderer)(int64)handle;
}
OSPCamera MPIDistributedDevice::newCamera(const char *type)
{
return createOSPRayObjectWithHandle<Camera, OSPCamera>(type);
}
OSPVolume MPIDistributedDevice::newVolume(const char *type)
{
return createOSPRayObjectWithHandle<Volume, OSPVolume>(type);
}
OSPGeometry MPIDistributedDevice::newGeometry(const char *type)
{
return createOSPRayObjectWithHandle<Geometry, OSPGeometry>(type);
}
OSPMaterial MPIDistributedDevice::newMaterial(OSPRenderer _renderer,
const char *type)
{
NOT_IMPLEMENTED;
}
OSPTransferFunction
MPIDistributedDevice::newTransferFunction(const char *type)
{
return createOSPRayObjectWithHandle<TransferFunction,
OSPTransferFunction>(type);
}
OSPLight MPIDistributedDevice::newLight(OSPRenderer _renderer,
const char *type)
{
auto &renderer = objectFromAPIHandle<Renderer>(_renderer);
auto *light = renderer.createLight(type);
if (light == nullptr)
light = Light::createLight(type);
if (light) {
ObjectHandle handle;
handle.assign(light);
return (OSPLight)(int64)handle;
} else {
return nullptr;
}
}
void MPIDistributedDevice::removeGeometry(OSPModel _model,
OSPGeometry _geometry)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &geom = objectFromAPIHandle<Geometry>(_geometry);
//TODO: confirm this works?
model.geometry.erase(std::remove(model.geometry.begin(),
model.geometry.end(),
Ref<Geometry>(&geom)));
}
void MPIDistributedDevice::removeVolume(OSPModel _model, OSPVolume _volume)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &volume = objectFromAPIHandle<Volume>(_volume);
//TODO: confirm this works?
model.volume.erase(std::remove(model.volume.begin(),
model.volume.end(),
Ref<Volume>(&volume)));
}
float MPIDistributedDevice::renderFrame(OSPFrameBuffer _fb,
OSPRenderer _renderer,
const uint32 fbChannelFlags)
{
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
auto &renderer = objectFromAPIHandle<Renderer>(_renderer);
auto result = renderer.renderFrame(&fb, fbChannelFlags);
mpicommon::world.barrier();
return result;
}
void MPIDistributedDevice::release(OSPObject _obj)
{
UNUSED(_obj);
postStatusMsg(1) << "WARNING: release() not implemented, memory leak!";
}
void MPIDistributedDevice::setMaterial(OSPGeometry _geometry,
OSPMaterial _material)
{
NOT_IMPLEMENTED;
}
OSPTexture2D MPIDistributedDevice::newTexture2D(
const vec2i &sz,
const OSPTextureFormat type,
void *data,
const uint32 flags
)
{
NOT_IMPLEMENTED;
}
void MPIDistributedDevice::sampleVolume(float **results,
OSPVolume volume,
const vec3f *worldCoordinates,
const size_t &count)
{
NOT_IMPLEMENTED;
}
OSP_REGISTER_DEVICE(MPIDistributedDevice, mpi_distributed_device);
OSP_REGISTER_DEVICE(MPIDistributedDevice, mpi_distributed);
} // ::ospray::mpi
} // ::ospray
<commit_msg>build fix for Windows<commit_after>// ======================================================================== //
// Copyright 2009-2017 Intel Corporation //
// //
// Licensed under the Apache License, Version 2.0 (the "License"); //
// you may not use this file except in compliance with the License. //
// You may obtain a copy of the License at //
// //
// http://www.apache.org/licenses/LICENSE-2.0 //
// //
// Unless required by applicable law or agreed to in writing, software //
// distributed under the License is distributed on an "AS IS" BASIS, //
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. //
// See the License for the specific language governing permissions and //
// limitations under the License. //
// ======================================================================== //
#undef NDEBUG // do all assertions in this file
//ospray
#include "ospray/camera/Camera.h"
#include "ospray/common/Data.h"
#include "ospray/lights/Light.h"
#include "ospray/transferFunction/TransferFunction.h"
//mpiCommon
#include "mpiCommon/MPICommon.h"
//ospray_mpi
#include "mpi/MPIDistributedDevice.h"
#include "mpi/fb/DistributedFrameBuffer.h"
#include "mpi/render/MPILoadBalancer.h"
//distributed objects
#include "render/distributed/DistributedRaycast.h"
#ifdef OPEN_MPI
# include <thread>
//# define _GNU_SOURCE
# include <sched.h>
#endif
namespace ospray {
namespace mpi {
// Helper functions ///////////////////////////////////////////////////////
template <typename OSPRAY_TYPE, typename API_TYPE>
inline API_TYPE createOSPRayObjectWithHandle(const char *type)
{
auto *instance = OSPRAY_TYPE::createInstance(type);
instance->refInc();
ObjectHandle handle;
handle.assign(instance);
return (API_TYPE)(int64)handle;
}
template <typename OSPRAY_TYPE>
inline OSPRAY_TYPE& objectFromAPIHandle(OSPObject obj)
{
auto &handle = reinterpret_cast<ObjectHandle&>(obj);
auto *object = (OSPRAY_TYPE*)handle.lookup();
if (!object)
throw std::runtime_error("#dmpi: ObjectHandle doesn't exist!");
return *object;
}
static void embreeErrorFunc(const RTCError code, const char* str)
{
postStatusMsg() << "#osp: embree internal error " << code << " : " << str;
throw std::runtime_error("embree internal error '" +std::string(str)+"'");
}
// MPIDistributedDevice definitions ///////////////////////////////////////
MPIDistributedDevice::~MPIDistributedDevice()
{
try {
MPI_CALL(Finalize());
} catch (...) {
//TODO: anything to do here? try-catch added to silence a warning...
}
}
void MPIDistributedDevice::commit()
{
if (!initialized) {
int _ac = 1;
const char *_av[] = {"ospray_mpi_worker"};
mpicommon::init(&_ac, _av);
std::stringstream embreeConfig;
if (debugMode)
embreeConfig << " threads=1,verbose=2";
else if(numThreads > 0)
embreeConfig << " threads=" << numThreads;
embreeDevice = rtcNewDevice(embreeConfig.str().c_str());
rtcDeviceSetErrorFunction(embreeDevice, embreeErrorFunc);
RTCError erc = rtcDeviceGetError(embreeDevice);
if (erc != RTC_NO_ERROR) {
// why did the error function not get called !?
postStatusMsg() << "#osp:init: embree internal error number " << erc;
assert(erc == RTC_NO_ERROR);
}
initialized = true;
}
Device::commit();
masterRank = getParam1i("masterRank", 0);
std::string mode = getParamString("mode", "distributed");
if (mode == "distributed") {
postStatusMsg() << "#dmpi: device commit() setting mode to " << mode;
} else {
throw std::runtime_error("#dmpi: bad device mode ['" + mode + "]");
}
// TODO: implement 'staticLoadBalancer::Distributed'
//TiledLoadBalancer::instance = make_unique<staticLoadBalancer::Master>();
}
OSPFrameBuffer
MPIDistributedDevice::frameBufferCreate(const vec2i &size,
const OSPFrameBufferFormat mode,
const uint32 channels)
{
const bool hasDepthBuffer = channels & OSP_FB_DEPTH;
const bool hasAccumBuffer = channels & OSP_FB_ACCUM;
const bool hasVarianceBuffer = channels & OSP_FB_VARIANCE;
ObjectHandle handle;
auto *instance = new DistributedFrameBuffer(size, handle, mode,
hasDepthBuffer,
hasAccumBuffer,
hasVarianceBuffer,
true);
instance->refInc();
handle.assign(instance);
return (OSPFrameBuffer)(int64)handle;
}
const void*
MPIDistributedDevice::frameBufferMap(OSPFrameBuffer _fb,
OSPFrameBufferChannel channel)
{
if (!mpicommon::IamTheMaster())
throw std::runtime_error("Can only map framebuffer on the master!");
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
switch (channel) {
case OSP_FB_COLOR: return fb.mapColorBuffer();
case OSP_FB_DEPTH: return fb.mapDepthBuffer();
default: return nullptr;
}
}
void MPIDistributedDevice::frameBufferUnmap(const void *mapped,
OSPFrameBuffer _fb)
{
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
fb.unmap(mapped);
}
void MPIDistributedDevice::frameBufferClear(OSPFrameBuffer _fb,
const uint32 fbChannelFlags)
{
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
fb.clear(fbChannelFlags);
}
OSPModel MPIDistributedDevice::newModel()
{
auto *instance = new Model;
instance->refInc();
ObjectHandle handle;
handle.assign(instance);
return (OSPModel)(int64)handle;
}
void MPIDistributedDevice::commit(OSPObject _object)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.commit();
}
void MPIDistributedDevice::addGeometry(OSPModel _model,
OSPGeometry _geometry)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &geom = objectFromAPIHandle<Geometry>(_geometry);
model.geometry.push_back(&geom);
}
void MPIDistributedDevice::addVolume(OSPModel _model, OSPVolume _volume)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &volume = objectFromAPIHandle<Volume>(_volume);
model.volume.push_back(&volume);
}
OSPData MPIDistributedDevice::newData(size_t nitems, OSPDataType format,
void *init, int flags)
{
ObjectHandle handle;
auto *instance = new Data(nitems, format, init, flags);
instance->refInc();
handle.assign(instance);
return (OSPData)(int64)handle;
}
void MPIDistributedDevice::setVoidPtr(OSPObject _object,
const char *bufName,
void *v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::removeParam(OSPObject _object, const char *name)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.removeParam(name);
}
int MPIDistributedDevice::setRegion(OSPVolume _volume, const void *source,
const vec3i &index, const vec3i &count)
{
auto &volume = objectFromAPIHandle<Volume>(_volume);
return volume.setRegion(source, index, count);
}
void MPIDistributedDevice::setString(OSPObject _object,
const char *bufName,
const char *s)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(s);
}
int MPIDistributedDevice::loadModule(const char *name)
{
return loadLocalModule(name);
}
void MPIDistributedDevice::setFloat(OSPObject _object,
const char *bufName,
const float f)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(f);
}
void MPIDistributedDevice::setInt(OSPObject _object,
const char *bufName,
const int i)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(i);
}
void MPIDistributedDevice::setVec2f(OSPObject _object,
const char *bufName,
const vec2f &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec3f(OSPObject _object,
const char *bufName,
const vec3f &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec4f(OSPObject _object,
const char *bufName,
const vec4f &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec2i(OSPObject _object,
const char *bufName,
const vec2i &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setVec3i(OSPObject _object,
const char *bufName,
const vec3i &v)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
object.findParam(bufName, true)->set(v);
}
void MPIDistributedDevice::setObject(OSPObject _object,
const char *bufName,
OSPObject _value)
{
auto &object = objectFromAPIHandle<ManagedObject>(_object);
auto &value = objectFromAPIHandle<ManagedObject>(_value);
object.set(bufName, &value);
}
OSPPixelOp MPIDistributedDevice::newPixelOp(const char *type)
{
NOT_IMPLEMENTED;
}
void MPIDistributedDevice::setPixelOp(OSPFrameBuffer _fb, OSPPixelOp _op)
{
NOT_IMPLEMENTED;
}
OSPRenderer MPIDistributedDevice::newRenderer(const char *type)
{
UNUSED(type);
auto *instance = new DistributedRaycastRenderer;
ObjectHandle handle;
handle.assign(instance);
return (OSPRenderer)(int64)handle;
}
OSPCamera MPIDistributedDevice::newCamera(const char *type)
{
return createOSPRayObjectWithHandle<Camera, OSPCamera>(type);
}
OSPVolume MPIDistributedDevice::newVolume(const char *type)
{
return createOSPRayObjectWithHandle<Volume, OSPVolume>(type);
}
OSPGeometry MPIDistributedDevice::newGeometry(const char *type)
{
return createOSPRayObjectWithHandle<Geometry, OSPGeometry>(type);
}
OSPMaterial MPIDistributedDevice::newMaterial(OSPRenderer _renderer,
const char *type)
{
NOT_IMPLEMENTED;
}
OSPTransferFunction
MPIDistributedDevice::newTransferFunction(const char *type)
{
return createOSPRayObjectWithHandle<TransferFunction,
OSPTransferFunction>(type);
}
OSPLight MPIDistributedDevice::newLight(OSPRenderer _renderer,
const char *type)
{
auto &renderer = objectFromAPIHandle<Renderer>(_renderer);
auto *light = renderer.createLight(type);
if (light == nullptr)
light = Light::createLight(type);
if (light) {
ObjectHandle handle;
handle.assign(light);
return (OSPLight)(int64)handle;
} else {
return nullptr;
}
}
void MPIDistributedDevice::removeGeometry(OSPModel _model,
OSPGeometry _geometry)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &geom = objectFromAPIHandle<Geometry>(_geometry);
//TODO: confirm this works?
model.geometry.erase(std::remove(model.geometry.begin(),
model.geometry.end(),
Ref<Geometry>(&geom)));
}
void MPIDistributedDevice::removeVolume(OSPModel _model, OSPVolume _volume)
{
auto &model = objectFromAPIHandle<Model>(_model);
auto &volume = objectFromAPIHandle<Volume>(_volume);
//TODO: confirm this works?
model.volume.erase(std::remove(model.volume.begin(),
model.volume.end(),
Ref<Volume>(&volume)));
}
float MPIDistributedDevice::renderFrame(OSPFrameBuffer _fb,
OSPRenderer _renderer,
const uint32 fbChannelFlags)
{
auto &fb = objectFromAPIHandle<FrameBuffer>(_fb);
auto &renderer = objectFromAPIHandle<Renderer>(_renderer);
auto result = renderer.renderFrame(&fb, fbChannelFlags);
mpicommon::world.barrier();
return result;
}
void MPIDistributedDevice::release(OSPObject _obj)
{
UNUSED(_obj);
postStatusMsg(1) << "WARNING: release() not implemented, memory leak!";
}
void MPIDistributedDevice::setMaterial(OSPGeometry _geometry,
OSPMaterial _material)
{
NOT_IMPLEMENTED;
}
OSPTexture2D MPIDistributedDevice::newTexture2D(
const vec2i &sz,
const OSPTextureFormat type,
void *data,
const uint32 flags
)
{
NOT_IMPLEMENTED;
}
void MPIDistributedDevice::sampleVolume(float **results,
OSPVolume volume,
const vec3f *worldCoordinates,
const size_t &count)
{
NOT_IMPLEMENTED;
}
OSP_REGISTER_DEVICE(MPIDistributedDevice, mpi_distributed_device);
OSP_REGISTER_DEVICE(MPIDistributedDevice, mpi_distributed);
} // ::ospray::mpi
} // ::ospray
<|endoftext|> |
<commit_before>#include <QString>
#include <QUrl>
#include <QFileInfo>
#include <QSqlQuery>
#include <QSqlRecord>
#include "identity.h"
#include "kernel.h"
#include "ilwisdata.h"
#include "resource.h"
#include "connectorinterface.h"
#include "catalogconnector.h"
#include "factory.h"
#include "abstractfactory.h"
#include "connectorfactory.h"
#include "catalog.h"
#include "catalogquery.h"
#include "ilwiscontext.h"
#include "mastercatalog.h"
using namespace Ilwis;
Catalog::Catalog(QObject *parent) :
QObject(parent)
{
}
Catalog::Catalog(const Catalog &cat) : QObject(),
Identity(cat.name(),cat.id(),cat.code(),cat.description()),
_filter(cat._filter),
_location(cat._location),
_parent(cat._parent)
{
}
std::list<Resource> Catalog::items() const
{
return mastercatalog()->select(_location, _filter);
}
bool Catalog::prepare(const QUrl &resource, const QString& filter)
{
bool ok = mastercatalog()->addContainer(resource);
if (!ok)
return false;
_location = resource;
CatalogQuery query;
_filter = query.transformQuery(filter);
QStringList parts = resource.path().split("/");
QString cid = parts.back();
setName(cid);
Identity::prepare();
return true;
}
QString Catalog::type() const
{
return "Catalog";
}
bool Catalog::isValid() const
{
return _location.isValid() && _filter != "";
}
IlwisTypes Catalog::ilwisType() const {
return itCATALOG;
}
QString Catalog::resolve(const QString &name, IlwisTypes tp) const
{
if ( name.contains(QRegExp("\\\\|/"))) { // is there already path info; check if it is the catalog
QString query = QString("select resource from mastecatalog where resource = '%2'").arg(name);
QSqlQuery results = kernel()->database().exec(query);
if ( results.next()) {
return name;
}
}
QString query = QString("select resource from mastercatalog where name = '%1' and (type & %2) != 0 and container='%3'").arg(name).arg(tp).arg(_location.toString());
if ( tp == itUNKNOWN) // incomplete info, we hope that the name will be unique. wrong selection must be handled at the caller side
query = QString("select resource from mastercatalog where name = '%1' and container='%2'").arg(name, _location.toString());
QSqlQuery results = kernel()->database().exec(query);
if ( results.next()) {
QSqlRecord rec = results.record();
return rec.value(0).toString();
}
return sUNDEF;
}
QUrl Catalog::parentCatalog() const
{
return _parent;
}
void Catalog::setParentCatalog(const QUrl &url)
{
_parent = url;
}
QUrl Catalog::location() const
{
return _location;
}
QUrl Catalog::filesystemLocation() const
{
if (_location.scheme() == "file")
return _location;
else
return context()->temporaryWorkLocation();
}
<commit_msg>added some extra info'comments<commit_after>#include <QString>
#include <QUrl>
#include <QFileInfo>
#include <QSqlQuery>
#include <QSqlRecord>
#include "identity.h"
#include "kernel.h"
#include "ilwisdata.h"
#include "resource.h"
#include "connectorinterface.h"
#include "catalogconnector.h"
#include "factory.h"
#include "abstractfactory.h"
#include "connectorfactory.h"
#include "catalog.h"
#include "catalogquery.h"
#include "ilwiscontext.h"
#include "mastercatalog.h"
using namespace Ilwis;
Catalog::Catalog(QObject *parent) :
QObject(parent)
{
}
Catalog::Catalog(const Catalog &cat) : QObject(),
Identity(cat.name(),cat.id(),cat.code(),cat.description()),
_filter(cat._filter),
_location(cat._location),
_parent(cat._parent)
{
}
std::list<Resource> Catalog::items() const
{
return mastercatalog()->select(_location, _filter);
}
bool Catalog::prepare(const QUrl &resource, const QString& filter)
{
bool ok = mastercatalog()->addContainer(resource);
if (!ok)
return false;
_location = resource;
CatalogQuery query;
_filter = query.transformQuery(filter);
QStringList parts = resource.path().split("/");
QString cid = parts.back();
setName(cid);
Identity::prepare();
return true;
}
QString Catalog::type() const
{
return "Catalog";
}
bool Catalog::isValid() const
{
return _location.isValid() && _filter != "";
}
IlwisTypes Catalog::ilwisType() const {
return itCATALOG;
}
QString Catalog::resolve(const QString &name, IlwisTypes tp) const
{
if ( name.contains(QRegExp("\\\\|/"))) { // is there already path info; check if it is the catalog
QString query = QString("select resource from mastecatalog where resource = '%2'").arg(name);
QSqlQuery results = kernel()->database().exec(query);
if ( results.next()) {
return name;
}
}
QString query = QString("select resource from mastercatalog where name = '%1' and (type & %2) != 0 and container='%3'").arg(name).arg(tp).arg(_location.toString());
if ( tp == itUNKNOWN) // incomplete info, we hope that the name will be unique. wrong selection must be handled at the caller side
query = QString("select resource from mastercatalog where name = '%1' and container='%2'").arg(name, _location.toString());
QSqlQuery results = kernel()->database().exec(query);
if ( results.next()) {
QSqlRecord rec = results.record();
return rec.value(0).toString();
} else {
auto resolvedName = name;
if ( context()->workingCatalog()) {
resolvedName = context()->workingCatalog()->location().toString() + "/" + name;
query = QString("select propertyvalue from catalogitemproperties,mastercatalog \
where mastercatalog.resource='%1' and mastercatalog.itemid=catalogitemproperties.itemid\
and (mastercatalog.extendedtype & %2) != 0").arg(resolvedName).arg(tp);
auto viaExtType = kernel()->database().exec(query);
if ( viaExtType.next()){ // if it is in the extended type than it is ok
return resolvedName;
}
}
return sUNDEF;
}
}
QUrl Catalog::parentCatalog() const
{
return _parent;
}
void Catalog::setParentCatalog(const QUrl &url)
{
_parent = url;
}
QUrl Catalog::location() const
{
return _location;
}
QUrl Catalog::filesystemLocation() const
{
if (_location.scheme() == "file")
return _location;
else
return context()->temporaryWorkLocation();
}
<|endoftext|> |
<commit_before>/**
* Appcelerator Titanium - licensed under the Apache Public License 2
* see LICENSE in the root folder for details on the license.
* Copyright (c) 2009 Appcelerator, Inc. All Rights Reserved.
*/
#include "async_copy.h"
#include "filesystem_binding.h"
#ifndef OS_WIN32
#include <unistd.h>
#include <string.h>
#include <errno.h>
#endif
namespace ti
{
AsyncCopy::AsyncCopy(
FilesystemBinding* parent,
Host *host,
std::vector<std::string> files,
std::string destination,
SharedBoundMethod callback)
: parent(parent),
host(host),
files(files),
destination(destination),
callback(callback),
stopped(false)
{
/**
* @tiapi(property=True,type=boolean,name=Filesystem.AsyncCopy.running,since=0.3) boolean property to indicate if the copy operation is running
*/
this->Set("running",Value::NewBool(true));
this->thread = new Poco::Thread();
this->thread->start(&AsyncCopy::Run,this);
}
AsyncCopy::~AsyncCopy()
{
if (this->thread!=NULL)
{
this->thread->tryJoin(10); // precaution, should already be stopped
delete this->thread;
this->thread = NULL;
}
}
void AsyncCopy::Copy(Poco::Path &src, Poco::Path &dest)
{
Poco::File from(src.toString());
#ifdef DEBUG
std::cout << "COPY: " << src.toString() << " => " << dest.toString() << " LINK=" << from.isLink() << std::endl;
#endif
if (from.isDirectory() && !from.isLink())
{
Poco::File d(dest.toString());
if (!d.exists())
{
d.createDirectories();
}
std::vector<std::string> files;
from.list(files);
std::vector<std::string>::iterator i = files.begin();
while(i!=files.end())
{
std::string fn = (*i++);
Poco::Path sp(kroll::FileUtils::Join(src.toString().c_str(),fn.c_str(),NULL));
Poco::Path dp(kroll::FileUtils::Join(dest.toString().c_str(),fn.c_str(),NULL));
this->Copy(sp,dp);
}
}
#ifndef OS_WIN32
else if (from.isLink())
{
char linkPath[PATH_MAX];
ssize_t length = readlink(from.path().c_str(), linkPath, PATH_MAX);
linkPath[length] = '\0';
std::string newPath (dest.toString());
const char *destPath = newPath.c_str();
// unlink it first, fails in some OS if already there
unlink(destPath);
int result = symlink(linkPath, destPath);
#ifdef DEBUG
std::cout << "Result: " << result << " for file: " << destPath << std::endl;
#endif
if (result == -1)
{
std::string err = "Copy failed: Could not make symlink (";
err.append(destPath);
err.append(") from ");
err.append(linkPath);
err.append(" : ");
err.append(strerror(errno));
throw kroll::ValueException::FromString(err);
}
}
#endif
else
{
// in this case it's a regular file
Poco::File s(src.toString());
s.copyTo(dest.toString().c_str());
}
}
void AsyncCopy::Run(void* data)
{
#ifdef OS_OSX
NSAutoreleasePool *pool = [[NSAutoreleasePool alloc] init];
#endif
AsyncCopy* ac = static_cast<AsyncCopy*>(data);
#ifdef DEBUG
std::cout << "async copy started with " << ac->files.size() << " files" << std::endl;
#endif
std::vector<std::string>::iterator iter = ac->files.begin();
Poco::Path to(ac->destination);
Poco::File tof(to.toString());
#ifdef DEBUG
std::cout << "ASYNC DEST: " << ac->destination << std::endl;
#endif
if (!tof.exists())
{
tof.createDirectory();
}
int c = 0;
while(!ac->stopped && iter!=ac->files.end())
{
std::string file = (*iter++);
c++;
#ifdef DEBUG
std::cout << "copying async file: " << file << " (" << c << "/" << ac->files.size() << ")" << std::endl;
#endif
try
{
Poco::Path from(file);
Poco::File f(file);
if (f.isDirectory())
{
ac->Copy(from,to);
}
else
{
Poco::Path dest(to,from.getFileName());
ac->Copy(from,dest);
}
#ifdef DEBUG
std::cout << "copied async file: " << file << " (" << c << "/" << ac->files.size() << ")" << std::endl;
#endif
SharedValue value = Value::NewString(file);
ValueList args;
args.push_back(value);
args.push_back(Value::NewInt(c));
args.push_back(Value::NewInt(ac->files.size()));
ac->host->InvokeMethodOnMainThread(ac->callback, args, false);
#ifdef DEBUG
std::cout << "after callback for async file: " << file << " (" << c << "/" << ac->files.size() << ")" << std::endl;
#endif
}
catch (ValueException &ex)
{
SharedString ss = ex.DisplayString();
std::cerr << "Error running async file copy: " << *ss << " for file: " << file << std::endl;
}
catch (Poco::Exception &ex)
{
std::cerr << "Error running async file copy: " << ex.displayText() << " for file: " << file << std::endl;
}
catch (std::exception &ex)
{
std::cerr << "Error running async file copy: " << ex.what() << " for file: " << file << std::endl;
}
catch (...)
{
std::cerr << "Unknown error running async file copy for file: " << file << std::endl;
}
}
ac->Set("running",Value::NewBool(false));
ac->stopped = true;
#ifdef DEBUG
std::cout << "async copy finished by copying " << c << " files" << std::endl;
#endif
#ifdef OS_OSX
[pool release];
#endif
}
void AsyncCopy::ToString(const ValueList& args, SharedValue result)
{
result->SetString("[Async Copy]");
}
void AsyncCopy::Cancel(const ValueList& args, SharedValue result)
{
KR_DUMP_LOCATION
if (thread!=NULL && thread->isRunning())
{
this->stopped = true;
this->Set("running",Value::NewBool(false));
result->SetBool(true);
}
else
{
result->SetBool(false);
}
}
}
<commit_msg>TI-157: Allow async copy to copy broken symlinks<commit_after>/**
* Appcelerator Titanium - licensed under the Apache Public License 2
* see LICENSE in the root folder for details on the license.
* Copyright (c) 2009 Appcelerator, Inc. All Rights Reserved.
*/
#include "async_copy.h"
#include "filesystem_binding.h"
#include <iostream>
#include <sstream>
#ifndef OS_WIN32
#include <unistd.h>
#include <string.h>
#include <errno.h>
#endif
namespace ti
{
AsyncCopy::AsyncCopy(
FilesystemBinding* parent,
Host *host,
std::vector<std::string> files,
std::string destination,
SharedBoundMethod callback)
: parent(parent),
host(host),
files(files),
destination(destination),
callback(callback),
stopped(false)
{
/**
* @tiapi(property=True,type=boolean,name=Filesystem.AsyncCopy.running,since=0.3) boolean property to indicate if the copy operation is running
*/
this->Set("running",Value::NewBool(true));
this->thread = new Poco::Thread();
this->thread->start(&AsyncCopy::Run,this);
}
AsyncCopy::~AsyncCopy()
{
if (this->thread!=NULL)
{
this->thread->tryJoin(10); // precaution, should already be stopped
delete this->thread;
this->thread = NULL;
}
}
void AsyncCopy::Copy(Poco::Path &src, Poco::Path &dest)
{
Logger& logger = Logger::Get("Filesystem.AsyncCopy");
std::string srcString = src.toString();
std::string destString = dest.toString();
Poco::File from(srcString);
bool isLink = from.isLink();
logger.Debug("file=%s dest=%s link=%i", srcString.c_str(), destString.c_str(), isLink);
#ifndef OS_WIN32
if (isLink)
{
char linkPath[PATH_MAX];
ssize_t length = readlink(from.path().c_str(), linkPath, PATH_MAX);
linkPath[length] = '\0';
std::string newPath (dest.toString());
const char *destPath = newPath.c_str();
unlink(destPath); // unlink it first, fails in some OS if already there
int result = symlink(linkPath, destPath);
if (result == -1)
{
std::string err = "Copy failed: Could not make symlink (";
err.append(destPath);
err.append(") from ");
err.append(linkPath);
err.append(" : ");
err.append(strerror(errno));
throw kroll::ValueException::FromString(err);
}
}
#endif
if (!isLink && from.isDirectory())
{
Poco::File d(dest.toString());
if (!d.exists())
{
d.createDirectories();
}
std::vector<std::string> files;
from.list(files);
std::vector<std::string>::iterator i = files.begin();
while(i!=files.end())
{
std::string fn = (*i++);
Poco::Path sp(kroll::FileUtils::Join(src.toString().c_str(),fn.c_str(),NULL));
Poco::Path dp(kroll::FileUtils::Join(dest.toString().c_str(),fn.c_str(),NULL));
this->Copy(sp,dp);
}
}
else if (!isLink)
{
// in this case it's a regular file
Poco::File s(src.toString());
s.copyTo(dest.toString().c_str());
}
}
void AsyncCopy::Run(void* data)
{
Logger& logger = Logger::Get("Filesystem.AsyncCopy");
#ifdef OS_OSX
NSAutoreleasePool *pool = [[NSAutoreleasePool alloc] init];
#endif
AsyncCopy* ac = static_cast<AsyncCopy*>(data);
std::vector<std::string>::iterator iter = ac->files.begin();
Poco::Path to(ac->destination);
Poco::File tof(to.toString());
logger.Debug("Job started: dest=%s, count=%i", ac->destination.c_str(), ac->files.size());
if (!tof.exists())
{
tof.createDirectory();
}
int c = 0;
while (!ac->stopped && iter!=ac->files.end())
{
std::string file = (*iter++);
c++;
logger.Debug("File: path=%s, count=%i\n", file.c_str(), c);
try
{
Poco::Path from(file);
Poco::File f(file);
if (f.isDirectory())
{
ac->Copy(from,to);
}
else
{
Poco::Path dest(to,from.getFileName());
ac->Copy(from,dest);
}
logger.Debug("File copied");
SharedValue value = Value::NewString(file);
ValueList args;
args.push_back(value);
args.push_back(Value::NewInt(c));
args.push_back(Value::NewInt(ac->files.size()));
ac->host->InvokeMethodOnMainThread(ac->callback, args, false);
logger.Debug("Callback executed");
}
catch (ValueException &ex)
{
SharedString ss = ex.DisplayString();
logger.Error(std::string("Error: ") + *ss + " for file: " + file);
}
catch (Poco::Exception &ex)
{
logger.Error(std::string("Error: ") + ex.displayText() + " for file: " + file);
}
catch (std::exception &ex)
{
logger.Error(std::string("Error: ") + ex.what() + " for file: " + file);
}
catch (...)
{
logger.Error(std::string("Unknown error during copy: ") + file);
}
}
ac->Set("running",Value::NewBool(false));
ac->stopped = true;
logger.Debug(std::string("Job finished"));
#ifdef OS_OSX
[pool release];
#endif
}
void AsyncCopy::ToString(const ValueList& args, SharedValue result)
{
result->SetString("[Async Copy]");
}
void AsyncCopy::Cancel(const ValueList& args, SharedValue result)
{
KR_DUMP_LOCATION
if (thread!=NULL && thread->isRunning())
{
this->stopped = true;
this->Set("running",Value::NewBool(false));
result->SetBool(true);
}
else
{
result->SetBool(false);
}
}
}
<|endoftext|> |
<commit_before>/*
Copyright (c) 2021 Advanced Micro Devices, Inc. All rights reserved.
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANNTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER INN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR INN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
/**
Testcase Scenarios :
1) Test hipMalloc() api passing zero size and confirming *ptr returning
nullptr. Also pass nullptr to hipFree() api.
2) Pass maximum value of size_t for hipMalloc() api and make sure appropriate
error is returned.
3) Check for hipMalloc() error code, passing invalid/null pointer.
4) Regress hipMalloc()/hipFree() in loop for bigger chunk of allocation
with adequate number of iterations and later test for kernel execution on
default gpu.
5) Regress hipMalloc()/hipFree() in loop while allocating smaller chunks
keeping maximum number of iterations and then run kernel code on default
gpu, perfom data validation.
6) Check hipMalloc() api adaptability when app creates small chunks of memory
continuously, stores it for later use and then frees it at later point
of time.
7) Multithread Scenario : Exercise hipMalloc() api parellely on all gpus from
multiple threads and regress the api.
8) Validate memory usage with hipMemGetInfo() while regressing hipMalloc()
api. Check for any possible memory leaks.
*/
#include <hip_test_common.hh>
#include <hip_test_checkers.hh>
#include <hip_test_kernels.hh>
#include <vector>
#include <limits>
#include <atomic>
/* Buffer size for bigger chunks in alloc/free cycles */
static constexpr auto BuffSizeBC = 5*1024*1024;
/* Buffer size for smaller chunks in alloc/free cycles */
static constexpr auto BuffSizeSC = 16;
/* You may change it for individual test.
* But default 100 is for quick return in Jenkin Build */
static constexpr auto NumDiv = 100;
/* Max alloc/free iterations for smaller chunks */
static constexpr auto MaxAllocFree_SmallChunks = (5000000/NumDiv);
/* Max alloc/free iterations for bigger chunks */
static constexpr auto MaxAllocFree_BigChunks = 10000;
/* Max alloc and pool iterations */
static constexpr auto MaxAllocPoolIter = (2000000/NumDiv);
/* Test status shared across threads */
static std::atomic<bool> g_thTestPassed{true};
/**
* Validates data consistency on supplied gpu
*/
static bool validateMemoryOnGPU(int gpu, bool concurOnOneGPU = false) {
int *A_d, *B_d, *C_d;
int *A_h, *B_h, *C_h;
size_t prevAvl, prevTot, curAvl, curTot;
bool TestPassed = true;
constexpr auto N = 4 * 1024 * 1024;
constexpr auto blocksPerCU = 6; // to hide latency
constexpr auto threadsPerBlock = 256;
size_t Nbytes = N * sizeof(int);
HIP_CHECK(hipSetDevice(gpu));
HIP_CHECK(hipMemGetInfo(&prevAvl, &prevTot));
HipTest::initArrays(&A_d, &B_d, &C_d, &A_h, &B_h, &C_h, N, false);
unsigned blocks = HipTest::setNumBlocks(blocksPerCU, threadsPerBlock, N);
HIP_CHECK(hipMemcpy(A_d, A_h, Nbytes, hipMemcpyHostToDevice));
HIP_CHECK(hipMemcpy(B_d, B_h, Nbytes, hipMemcpyHostToDevice));
hipLaunchKernelGGL(HipTest::vectorADD, dim3(blocks), dim3(threadsPerBlock),
0, 0, static_cast<const int*>(A_d),
static_cast<const int*>(B_d), C_d, N);
HIP_CHECK(hipMemcpy(C_h, C_d, Nbytes, hipMemcpyDeviceToHost));
if (!HipTest::checkVectorADD(A_h, B_h, C_h, N)) {
UNSCOPED_INFO("Validation PASSED for gpu " << gpu);
} else {
UNSCOPED_INFO("Validation FAILED for gpu " << gpu);
TestPassed = false;
}
HipTest::freeArrays(A_d, B_d, C_d, A_h, B_h, C_h, false);
HIP_CHECK(hipMemGetInfo(&curAvl, &curTot));
if (!concurOnOneGPU && (prevAvl != curAvl || prevTot != curTot)) {
// In concurrent calls on one GPU, we cannot verify leaking in this way
UNSCOPED_INFO(
"validateMemoryOnGPU : Memory allocation mismatch observed."
<< "Possible memory leak.");
TestPassed = false;
}
return TestPassed;
}
/**
* Regress memory allocation and free in loop
*/
static bool regressAllocInLoop(int gpu) {
bool TestPassed = true;
size_t tot, avail, ptot, pavail, numBytes;
int i = 0;
int *ptr;
HIP_CHECK(hipSetDevice(gpu));
numBytes = BuffSizeBC;
// Exercise allocation in loop with bigger chunks
for (i = 0; i < MaxAllocFree_BigChunks; i++) {
HIP_CHECK(hipMemGetInfo(&pavail, &ptot));
HIP_CHECK(hipMalloc(&ptr, numBytes));
HIP_CHECK(hipMemGetInfo(&avail, &tot));
HIP_CHECK(hipFree(ptr));
if (pavail-avail < numBytes) { // We expect pavail-avail >= numBytes
UNSCOPED_INFO("LoopAllocation " << i << " : Memory allocation of " <<
numBytes << " not matching with hipMemGetInfo - FAIL." << "pavail=" <<
pavail << ", ptot=" << ptot << ", avail=" << avail << ", tot=" <<
tot << ", pavail-avail=" << pavail-avail);
TestPassed = false;
break;
}
}
// Exercise allocation in loop with smaller chunks and maximum iters
HIP_CHECK(hipMemGetInfo(&pavail, &ptot));
numBytes = BuffSizeSC;
for (i = 0; i < MaxAllocFree_SmallChunks; i++) {
HIP_CHECK(hipMalloc(&ptr, numBytes));
HIP_CHECK(hipFree(ptr));
}
HIP_CHECK(hipMemGetInfo(&avail, &tot));
if ((pavail != avail) || (ptot != tot)) {
UNSCOPED_INFO("LoopAllocation : Memory allocation mismatch observed." <<
"Possible memory leak.");
TestPassed &= false;
}
return TestPassed;
}
/**
* Validates data consistency on supplied gpu
* In Multithreaded Environment
*/
static bool validateMemoryOnGpuMThread(int gpu, bool concurOnOneGPU = false) {
int *A_d, *B_d, *C_d;
int *A_h, *B_h, *C_h;
size_t prevAvl, prevTot, curAvl, curTot;
bool TestPassed = true;
constexpr auto N = 4 * 1024 * 1024;
constexpr auto blocksPerCU = 6; // to hide latency
constexpr auto threadsPerBlock = 256;
size_t Nbytes = N * sizeof(int);
HIPCHECK(hipSetDevice(gpu));
HIPCHECK(hipMemGetInfo(&prevAvl, &prevTot));
HipTest::initArrays(&A_d, &B_d, &C_d, &A_h, &B_h, &C_h, N, false);
unsigned blocks = HipTest::setNumBlocks(blocksPerCU, threadsPerBlock, N);
HIPCHECK(hipMemcpy(A_d, A_h, Nbytes, hipMemcpyHostToDevice));
HIPCHECK(hipMemcpy(B_d, B_h, Nbytes, hipMemcpyHostToDevice));
hipLaunchKernelGGL(HipTest::vectorADD, dim3(blocks), dim3(threadsPerBlock),
0, 0, static_cast<const int*>(A_d),
static_cast<const int*>(B_d), C_d, N);
HIPCHECK(hipMemcpy(C_h, C_d, Nbytes, hipMemcpyDeviceToHost));
if (!HipTest::checkVectorADD(A_h, B_h, C_h, N)) {
UNSCOPED_INFO("Validation PASSED for gpu " << gpu);
} else {
UNSCOPED_INFO("Validation FAILED for gpu " << gpu);
TestPassed = false;
}
HipTest::freeArrays(A_d, B_d, C_d, A_h, B_h, C_h, false);
HIPCHECK(hipMemGetInfo(&curAvl, &curTot));
if (!concurOnOneGPU && (prevAvl != curAvl || prevTot != curTot)) {
// In concurrent calls on one GPU, we cannot verify leaking in this way
UNSCOPED_INFO(
"validateMemoryOnGpuMThread : Memory allocation mismatch observed."
"Possible memory leak.");
TestPassed = false;
}
return TestPassed;
}
/**
* Regress memory allocation and free in loop
* In Multithreaded Environment
*/
static bool regressAllocInLoopMthread(int gpu) {
bool TestPassed = true;
size_t tot, avail, ptot, pavail, numBytes;
int i = 0;
int *ptr;
HIPCHECK(hipSetDevice(gpu));
numBytes = BuffSizeBC;
// Exercise allocation in loop with bigger chunks
for (i = 0; i < MaxAllocFree_BigChunks; i++) {
HIPCHECK(hipMemGetInfo(&pavail, &ptot));
HIPCHECK(hipMalloc(&ptr, numBytes));
HIPCHECK(hipMemGetInfo(&avail, &tot));
HIPCHECK(hipFree(ptr));
if (pavail-avail < numBytes) { // We expect pavail-avail >= numBytes
UNSCOPED_INFO("LoopAllocation " << i << " : Memory allocation of " <<
numBytes << " not matching with hipMemGetInfo - FAIL." << "pavail=" <<
pavail << ", ptot=" << ptot << ", avail=" << avail << ", tot=" <<
tot << ", pavail-avail=" << pavail-avail);
TestPassed = false;
break;
}
}
// Exercise allocation in loop with smaller chunks and maximum iters
HIPCHECK(hipMemGetInfo(&pavail, &ptot));
numBytes = BuffSizeSC;
for (i = 0; i < MaxAllocFree_SmallChunks; i++) {
HIPCHECK(hipMalloc(&ptr, numBytes));
HIPCHECK(hipFree(ptr));
}
HIPCHECK(hipMemGetInfo(&avail, &tot));
if ((pavail != avail) || (ptot != tot)) {
UNSCOPED_INFO("LoopAllocation : Memory allocation mismatch observed." <<
"Possible memory leak.");
TestPassed &= false;
}
return TestPassed;
}
/*
* Thread func to regress alloc and check data consistency
*/
static void threadFunc(int gpu) {
g_thTestPassed = regressAllocInLoopMthread(gpu);
g_thTestPassed = g_thTestPassed & validateMemoryOnGpuMThread(gpu);
UNSCOPED_INFO("thread execution status on gpu" << gpu << ":" <<
g_thTestPassed.load());
}
/* Performs Argument Validation of api */
TEST_CASE("Unit_hipMalloc_ArgumentValidation") {
int *ptr;
hipError_t ret;
SECTION("hipMalloc() when size(0)") {
HIP_CHECK(hipMalloc(&ptr, 0));
// ptr expected to be reset to null ptr
REQUIRE(ptr == nullptr);
}
SECTION("hipFree() when freeing nullptr ") {
ptr = nullptr;
// api should return success and shudnt crash
HIP_CHECK(hipFree(ptr));
}
SECTION("hipMalloc() with invalid argument") {
constexpr auto sizeBytes = 100;
ret = hipMalloc(nullptr, sizeBytes);
REQUIRE(ret != hipSuccess);
}
SECTION("hipMalloc() with max size_t") {
ret = hipMalloc(&ptr, std::numeric_limits<std::size_t>::max());
REQUIRE(ret != hipSuccess);
}
}
/**
* Regress hipMalloc()/hipFree() in loop for bigger chunks and
* smaller chunks of memory allocation
*/
TEST_CASE("Unit_hipMalloc_LoopRegressionAllocFreeCycles") {
int devCnt = 0;
// Get GPU count
HIP_CHECK(hipGetDeviceCount(&devCnt));
REQUIRE(devCnt > 0);
CHECK(regressAllocInLoop(0) == true);
CHECK(validateMemoryOnGPU(0) == true);
}
/**
* Application Behavior Modelling.
* Check hipMalloc() api adaptability when app creates small chunks of memory
* continuously, stores it for later use and then frees it at later point
* of time.
*/
TEST_CASE("Unit_hipMalloc_AllocateAndPoolBuffers") {
size_t avail, tot, pavail, ptot;
bool ret;
hipError_t err;
std::vector<int *> ptrlist;
constexpr auto BuffSize = 10;
int devCnt, *ptr;
// Get GPU count
HIP_CHECK(hipGetDeviceCount(&devCnt));
REQUIRE(devCnt > 0);
HIP_CHECK(hipMemGetInfo(&pavail, &ptot));
// Allocate small chunks of memory million times
for (int i = 0; i < MaxAllocPoolIter ; i++) {
if ((err = hipMalloc(&ptr, BuffSize)) != hipSuccess) {
HIP_CHECK(hipMemGetInfo(&avail, &tot));
INFO("Loop regression pool allocation failure. " <<
"Total gpu memory " << tot/(1024.0*1024.0) <<", Free memory " <<
avail/(1024.0*1024.0) << " iter " << i << " error "
<< hipGetErrorString(err));
REQUIRE(false);
}
// Store pointers allocated to emulate memory pool of app
ptrlist.push_back(ptr);
}
// Free ptrs at later point of time
for ( auto &t : ptrlist ) {
HIP_CHECK(hipFree(t));
}
HIP_CHECK(hipMemGetInfo(&avail, &tot));
ret = validateMemoryOnGPU(0);
REQUIRE(ret == true);
REQUIRE(pavail == avail);
REQUIRE(ptot == tot);
}
/**
* Exercise hipMalloc() api parellely on all gpus from
* multiple threads and regress the api.
*/
TEST_CASE("Unit_hipMalloc_Multithreaded_MultiGPU") {
std::vector<std::thread> threadlist;
int devCnt;
// Get GPU count
HIP_CHECK(hipGetDeviceCount(&devCnt));
REQUIRE(devCnt > 0);
for (int i = 0; i < devCnt; i++) {
threadlist.push_back(std::thread(threadFunc, i));
}
for (auto &t : threadlist) {
t.join();
}
REQUIRE(g_thTestPassed == true);
}
<commit_msg>SWDEV-309676 - Fix for build failure due to new compiler flag -Wbitwise-instead-of-logical (#2443)<commit_after>/*
Copyright (c) 2021 Advanced Micro Devices, Inc. All rights reserved.
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANNTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER INN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR INN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
/**
Testcase Scenarios :
1) Test hipMalloc() api passing zero size and confirming *ptr returning
nullptr. Also pass nullptr to hipFree() api.
2) Pass maximum value of size_t for hipMalloc() api and make sure appropriate
error is returned.
3) Check for hipMalloc() error code, passing invalid/null pointer.
4) Regress hipMalloc()/hipFree() in loop for bigger chunk of allocation
with adequate number of iterations and later test for kernel execution on
default gpu.
5) Regress hipMalloc()/hipFree() in loop while allocating smaller chunks
keeping maximum number of iterations and then run kernel code on default
gpu, perfom data validation.
6) Check hipMalloc() api adaptability when app creates small chunks of memory
continuously, stores it for later use and then frees it at later point
of time.
7) Multithread Scenario : Exercise hipMalloc() api parellely on all gpus from
multiple threads and regress the api.
8) Validate memory usage with hipMemGetInfo() while regressing hipMalloc()
api. Check for any possible memory leaks.
*/
#include <hip_test_common.hh>
#include <hip_test_checkers.hh>
#include <hip_test_kernels.hh>
#include <vector>
#include <limits>
#include <atomic>
/* Buffer size for bigger chunks in alloc/free cycles */
static constexpr auto BuffSizeBC = 5*1024*1024;
/* Buffer size for smaller chunks in alloc/free cycles */
static constexpr auto BuffSizeSC = 16;
/* You may change it for individual test.
* But default 100 is for quick return in Jenkin Build */
static constexpr auto NumDiv = 100;
/* Max alloc/free iterations for smaller chunks */
static constexpr auto MaxAllocFree_SmallChunks = (5000000/NumDiv);
/* Max alloc/free iterations for bigger chunks */
static constexpr auto MaxAllocFree_BigChunks = 10000;
/* Max alloc and pool iterations */
static constexpr auto MaxAllocPoolIter = (2000000/NumDiv);
/* Test status shared across threads */
static std::atomic<bool> g_thTestPassed{true};
/**
* Validates data consistency on supplied gpu
*/
static bool validateMemoryOnGPU(int gpu, bool concurOnOneGPU = false) {
int *A_d, *B_d, *C_d;
int *A_h, *B_h, *C_h;
size_t prevAvl, prevTot, curAvl, curTot;
bool TestPassed = true;
constexpr auto N = 4 * 1024 * 1024;
constexpr auto blocksPerCU = 6; // to hide latency
constexpr auto threadsPerBlock = 256;
size_t Nbytes = N * sizeof(int);
HIP_CHECK(hipSetDevice(gpu));
HIP_CHECK(hipMemGetInfo(&prevAvl, &prevTot));
HipTest::initArrays(&A_d, &B_d, &C_d, &A_h, &B_h, &C_h, N, false);
unsigned blocks = HipTest::setNumBlocks(blocksPerCU, threadsPerBlock, N);
HIP_CHECK(hipMemcpy(A_d, A_h, Nbytes, hipMemcpyHostToDevice));
HIP_CHECK(hipMemcpy(B_d, B_h, Nbytes, hipMemcpyHostToDevice));
hipLaunchKernelGGL(HipTest::vectorADD, dim3(blocks), dim3(threadsPerBlock),
0, 0, static_cast<const int*>(A_d),
static_cast<const int*>(B_d), C_d, N);
HIP_CHECK(hipMemcpy(C_h, C_d, Nbytes, hipMemcpyDeviceToHost));
if (!HipTest::checkVectorADD(A_h, B_h, C_h, N)) {
UNSCOPED_INFO("Validation PASSED for gpu " << gpu);
} else {
UNSCOPED_INFO("Validation FAILED for gpu " << gpu);
TestPassed = false;
}
HipTest::freeArrays(A_d, B_d, C_d, A_h, B_h, C_h, false);
HIP_CHECK(hipMemGetInfo(&curAvl, &curTot));
if (!concurOnOneGPU && (prevAvl != curAvl || prevTot != curTot)) {
// In concurrent calls on one GPU, we cannot verify leaking in this way
UNSCOPED_INFO(
"validateMemoryOnGPU : Memory allocation mismatch observed."
<< "Possible memory leak.");
TestPassed = false;
}
return TestPassed;
}
/**
* Regress memory allocation and free in loop
*/
static bool regressAllocInLoop(int gpu) {
bool TestPassed = true;
size_t tot, avail, ptot, pavail, numBytes;
int i = 0;
int *ptr;
HIP_CHECK(hipSetDevice(gpu));
numBytes = BuffSizeBC;
// Exercise allocation in loop with bigger chunks
for (i = 0; i < MaxAllocFree_BigChunks; i++) {
HIP_CHECK(hipMemGetInfo(&pavail, &ptot));
HIP_CHECK(hipMalloc(&ptr, numBytes));
HIP_CHECK(hipMemGetInfo(&avail, &tot));
HIP_CHECK(hipFree(ptr));
if (pavail-avail < numBytes) { // We expect pavail-avail >= numBytes
UNSCOPED_INFO("LoopAllocation " << i << " : Memory allocation of " <<
numBytes << " not matching with hipMemGetInfo - FAIL." << "pavail=" <<
pavail << ", ptot=" << ptot << ", avail=" << avail << ", tot=" <<
tot << ", pavail-avail=" << pavail-avail);
TestPassed = false;
break;
}
}
// Exercise allocation in loop with smaller chunks and maximum iters
HIP_CHECK(hipMemGetInfo(&pavail, &ptot));
numBytes = BuffSizeSC;
for (i = 0; i < MaxAllocFree_SmallChunks; i++) {
HIP_CHECK(hipMalloc(&ptr, numBytes));
HIP_CHECK(hipFree(ptr));
}
HIP_CHECK(hipMemGetInfo(&avail, &tot));
if ((pavail != avail) || (ptot != tot)) {
UNSCOPED_INFO("LoopAllocation : Memory allocation mismatch observed." <<
"Possible memory leak.");
TestPassed &= false;
}
return TestPassed;
}
/**
* Validates data consistency on supplied gpu
* In Multithreaded Environment
*/
static bool validateMemoryOnGpuMThread(int gpu, bool concurOnOneGPU = false) {
int *A_d, *B_d, *C_d;
int *A_h, *B_h, *C_h;
size_t prevAvl, prevTot, curAvl, curTot;
bool TestPassed = true;
constexpr auto N = 4 * 1024 * 1024;
constexpr auto blocksPerCU = 6; // to hide latency
constexpr auto threadsPerBlock = 256;
size_t Nbytes = N * sizeof(int);
HIPCHECK(hipSetDevice(gpu));
HIPCHECK(hipMemGetInfo(&prevAvl, &prevTot));
HipTest::initArrays(&A_d, &B_d, &C_d, &A_h, &B_h, &C_h, N, false);
unsigned blocks = HipTest::setNumBlocks(blocksPerCU, threadsPerBlock, N);
HIPCHECK(hipMemcpy(A_d, A_h, Nbytes, hipMemcpyHostToDevice));
HIPCHECK(hipMemcpy(B_d, B_h, Nbytes, hipMemcpyHostToDevice));
hipLaunchKernelGGL(HipTest::vectorADD, dim3(blocks), dim3(threadsPerBlock),
0, 0, static_cast<const int*>(A_d),
static_cast<const int*>(B_d), C_d, N);
HIPCHECK(hipMemcpy(C_h, C_d, Nbytes, hipMemcpyDeviceToHost));
if (!HipTest::checkVectorADD(A_h, B_h, C_h, N)) {
UNSCOPED_INFO("Validation PASSED for gpu " << gpu);
} else {
UNSCOPED_INFO("Validation FAILED for gpu " << gpu);
TestPassed = false;
}
HipTest::freeArrays(A_d, B_d, C_d, A_h, B_h, C_h, false);
HIPCHECK(hipMemGetInfo(&curAvl, &curTot));
if (!concurOnOneGPU && (prevAvl != curAvl || prevTot != curTot)) {
// In concurrent calls on one GPU, we cannot verify leaking in this way
UNSCOPED_INFO(
"validateMemoryOnGpuMThread : Memory allocation mismatch observed."
"Possible memory leak.");
TestPassed = false;
}
return TestPassed;
}
/**
* Regress memory allocation and free in loop
* In Multithreaded Environment
*/
static bool regressAllocInLoopMthread(int gpu) {
bool TestPassed = true;
size_t tot, avail, ptot, pavail, numBytes;
int i = 0;
int *ptr;
HIPCHECK(hipSetDevice(gpu));
numBytes = BuffSizeBC;
// Exercise allocation in loop with bigger chunks
for (i = 0; i < MaxAllocFree_BigChunks; i++) {
HIPCHECK(hipMemGetInfo(&pavail, &ptot));
HIPCHECK(hipMalloc(&ptr, numBytes));
HIPCHECK(hipMemGetInfo(&avail, &tot));
HIPCHECK(hipFree(ptr));
if (pavail-avail < numBytes) { // We expect pavail-avail >= numBytes
UNSCOPED_INFO("LoopAllocation " << i << " : Memory allocation of " <<
numBytes << " not matching with hipMemGetInfo - FAIL." << "pavail=" <<
pavail << ", ptot=" << ptot << ", avail=" << avail << ", tot=" <<
tot << ", pavail-avail=" << pavail-avail);
TestPassed = false;
break;
}
}
// Exercise allocation in loop with smaller chunks and maximum iters
HIPCHECK(hipMemGetInfo(&pavail, &ptot));
numBytes = BuffSizeSC;
for (i = 0; i < MaxAllocFree_SmallChunks; i++) {
HIPCHECK(hipMalloc(&ptr, numBytes));
HIPCHECK(hipFree(ptr));
}
HIPCHECK(hipMemGetInfo(&avail, &tot));
if ((pavail != avail) || (ptot != tot)) {
UNSCOPED_INFO("LoopAllocation : Memory allocation mismatch observed." <<
"Possible memory leak.");
TestPassed &= false;
}
return TestPassed;
}
/*
* Thread func to regress alloc and check data consistency
*/
static void threadFunc(int gpu) {
g_thTestPassed = regressAllocInLoopMthread(gpu)
&& validateMemoryOnGpuMThread(gpu);
UNSCOPED_INFO("thread execution status on gpu" << gpu << ":" <<
g_thTestPassed.load());
}
/* Performs Argument Validation of api */
TEST_CASE("Unit_hipMalloc_ArgumentValidation") {
int *ptr;
hipError_t ret;
SECTION("hipMalloc() when size(0)") {
HIP_CHECK(hipMalloc(&ptr, 0));
// ptr expected to be reset to null ptr
REQUIRE(ptr == nullptr);
}
SECTION("hipFree() when freeing nullptr ") {
ptr = nullptr;
// api should return success and shudnt crash
HIP_CHECK(hipFree(ptr));
}
SECTION("hipMalloc() with invalid argument") {
constexpr auto sizeBytes = 100;
ret = hipMalloc(nullptr, sizeBytes);
REQUIRE(ret != hipSuccess);
}
SECTION("hipMalloc() with max size_t") {
ret = hipMalloc(&ptr, std::numeric_limits<std::size_t>::max());
REQUIRE(ret != hipSuccess);
}
}
/**
* Regress hipMalloc()/hipFree() in loop for bigger chunks and
* smaller chunks of memory allocation
*/
TEST_CASE("Unit_hipMalloc_LoopRegressionAllocFreeCycles") {
int devCnt = 0;
// Get GPU count
HIP_CHECK(hipGetDeviceCount(&devCnt));
REQUIRE(devCnt > 0);
CHECK(regressAllocInLoop(0) == true);
CHECK(validateMemoryOnGPU(0) == true);
}
/**
* Application Behavior Modelling.
* Check hipMalloc() api adaptability when app creates small chunks of memory
* continuously, stores it for later use and then frees it at later point
* of time.
*/
TEST_CASE("Unit_hipMalloc_AllocateAndPoolBuffers") {
size_t avail, tot, pavail, ptot;
bool ret;
hipError_t err;
std::vector<int *> ptrlist;
constexpr auto BuffSize = 10;
int devCnt, *ptr;
// Get GPU count
HIP_CHECK(hipGetDeviceCount(&devCnt));
REQUIRE(devCnt > 0);
HIP_CHECK(hipMemGetInfo(&pavail, &ptot));
// Allocate small chunks of memory million times
for (int i = 0; i < MaxAllocPoolIter ; i++) {
if ((err = hipMalloc(&ptr, BuffSize)) != hipSuccess) {
HIP_CHECK(hipMemGetInfo(&avail, &tot));
INFO("Loop regression pool allocation failure. " <<
"Total gpu memory " << tot/(1024.0*1024.0) <<", Free memory " <<
avail/(1024.0*1024.0) << " iter " << i << " error "
<< hipGetErrorString(err));
REQUIRE(false);
}
// Store pointers allocated to emulate memory pool of app
ptrlist.push_back(ptr);
}
// Free ptrs at later point of time
for ( auto &t : ptrlist ) {
HIP_CHECK(hipFree(t));
}
HIP_CHECK(hipMemGetInfo(&avail, &tot));
ret = validateMemoryOnGPU(0);
REQUIRE(ret == true);
REQUIRE(pavail == avail);
REQUIRE(ptot == tot);
}
/**
* Exercise hipMalloc() api parellely on all gpus from
* multiple threads and regress the api.
*/
TEST_CASE("Unit_hipMalloc_Multithreaded_MultiGPU") {
std::vector<std::thread> threadlist;
int devCnt;
// Get GPU count
HIP_CHECK(hipGetDeviceCount(&devCnt));
REQUIRE(devCnt > 0);
for (int i = 0; i < devCnt; i++) {
threadlist.push_back(std::thread(threadFunc, i));
}
for (auto &t : threadlist) {
t.join();
}
REQUIRE(g_thTestPassed == true);
}
<|endoftext|> |
<commit_before>/* This file is part of Ingen.
* Copyright (C) 2007 Dave Robillard <http://drobilla.net>
*
* Ingen is free software; you can redistribute it and/or modify it under the
* terms of the GNU General Public License as published by the Free Software
* Foundation; either version 2 of the License, or (at your option) any later
* version.
*
* Ingen is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
* FOR A PARTICULAR PURPOSE. See the GNU General Public License for details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include <sstream>
#include <lv2ext/lv2_event.h>
#include "Responder.hpp"
#include "SetPortValueEvent.hpp"
#include "Engine.hpp"
#include "PortImpl.hpp"
#include "ClientBroadcaster.hpp"
#include "NodeImpl.hpp"
#include "EngineStore.hpp"
#include "AudioBuffer.hpp"
#include "EventBuffer.hpp"
#include "ProcessContext.hpp"
#include "MessageContext.hpp"
using namespace std;
namespace Ingen {
/** Omni (all voices) control setting */
SetPortValueEvent::SetPortValueEvent(Engine& engine,
SharedPtr<Responder> responder,
bool queued,
SampleCount timestamp,
const string& port_path,
const Raul::Atom& value)
: QueuedEvent(engine, responder, timestamp)
, _queued(queued)
, _omni(true)
, _voice_num(0)
, _port_path(port_path)
, _value(value)
, _port(NULL)
, _error(NO_ERROR)
{
}
/** Voice-specific control setting */
SetPortValueEvent::SetPortValueEvent(Engine& engine,
SharedPtr<Responder> responder,
bool queued,
SampleCount timestamp,
uint32_t voice_num,
const string& port_path,
const Raul::Atom& value)
: QueuedEvent(engine, responder, timestamp)
, _queued(queued)
, _omni(false)
, _voice_num(voice_num)
, _port_path(port_path)
, _value(value)
, _port(NULL)
, _error(NO_ERROR)
{
}
SetPortValueEvent::~SetPortValueEvent()
{
}
void
SetPortValueEvent::pre_process()
{
if (_queued) {
if (_port == NULL) {
if (Path::is_valid(_port_path))
_port = _engine.engine_store()->find_port(_port_path);
else
_error = ILLEGAL_PATH;
}
if (_port == NULL && _error == NO_ERROR)
_error = PORT_NOT_FOUND;
}
// Port is a message context port, set its value and
// call the plugin's message run function once
if (_port && _port->context() == Context::MESSAGE) {
_engine.message_context()->run(_port->parent_node());
}
QueuedEvent::pre_process();
}
void
SetPortValueEvent::execute(ProcessContext& context)
{
Event::execute(context);
assert(_time >= context.start() && _time <= context.end());
if (_port && _port->context() == Context::MESSAGE)
return;
if (_error == NO_ERROR && _port == NULL) {
if (Path::is_valid(_port_path))
_port = _engine.engine_store()->find_port(_port_path);
else
_error = ILLEGAL_PATH;
}
if (_port == NULL) {
if (_error == NO_ERROR)
_error = PORT_NOT_FOUND;
/*} else if (_port->buffer(0)->capacity() < _data_size) {
_error = NO_SPACE;*/
} else {
Buffer* const buf = _port->buffer(0);
AudioBuffer* const abuf = dynamic_cast<AudioBuffer*>(buf);
if (abuf) {
if (_value.type() != Atom::FLOAT) {
_error = TYPE_MISMATCH;
return;
}
if (_omni) {
for (uint32_t i=0; i < _port->poly(); ++i)
((AudioBuffer*)_port->buffer(i))->set_value(
_value.get_float(), context.start(), _time);
} else {
if (_voice_num < _port->poly())
((AudioBuffer*)_port->buffer(_voice_num))->set_value(
_value.get_float(), context.start(), _time);
else
_error = ILLEGAL_VOICE;
}
return;
}
EventBuffer* const ebuf = dynamic_cast<EventBuffer*>(buf);
const LV2Features::Feature* f = _engine.world()->lv2_features->feature(LV2_URI_MAP_URI);
LV2URIMap* map = (LV2URIMap*)f->controller;
// FIXME: eliminate lookups
// FIXME: need a proper prefix system
if (ebuf && _value.type() == Atom::BLOB) {
const uint32_t frames = std::max(
(uint32_t)(_time - context.start()),
ebuf->latest_frames());
// Size 0 event, pass it along to the plugin as a typed but empty event
if (_value.data_size() == 0) {
cout << "BANG!" << endl;
const uint32_t type_id = map->uri_to_id(NULL, _value.get_blob_type());
ebuf->append(frames, 0, type_id, 0, NULL);
_port->raise_set_by_user_flag();
return;
} else if (!strcmp(_value.get_blob_type(), "lv2_midi:MidiEvent")) {
const uint32_t type_id = map->uri_to_id(NULL,
"http://lv2plug.in/ns/ext/midi#MidiEvent");
ebuf->prepare_write(context.start(), context.nframes());
// FIXME: use OSC midi type? avoid MIDI over OSC entirely?
ebuf->append(frames, 0, type_id, _value.data_size(),
(const uint8_t*)_value.get_blob());
_port->raise_set_by_user_flag();
return;
}
}
if (_value.type() == Atom::BLOB)
cerr << "WARNING: Unknown value blob type " << _value.get_blob_type() << endl;
else
cerr << "WARNING: Unknown value type " << (int)_value.type() << endl;
}
}
void
SetPortValueEvent::post_process()
{
if (_error == NO_ERROR) {
assert(_port != NULL);
_responder->respond_ok();
_engine.broadcaster()->send_port_value(_port_path, _value);
} else if (_error == ILLEGAL_PATH) {
string msg = "Illegal port path \"";
msg.append(_port_path).append("\"");
_responder->respond_error(msg);
} else if (_error == ILLEGAL_VOICE) {
std::ostringstream ss;
ss << "Illegal voice number " << _voice_num;
_responder->respond_error(ss.str());
} else if (_error == PORT_NOT_FOUND) {
string msg = "Unable to find port ";
msg.append(_port_path).append(" for set_port_value");
_responder->respond_error(msg);
} else if (_error == NO_SPACE) {
std::ostringstream msg("Attempt to write ");
msg << _value.data_size() << " bytes to " << _port_path << ", with capacity "
<< _port->buffer_size() << endl;
_responder->respond_error(msg.str());
}
}
} // namespace Ingen
<commit_msg>More waf.<commit_after>/* This file is part of Ingen.
* Copyright (C) 2007 Dave Robillard <http://drobilla.net>
*
* Ingen is free software; you can redistribute it and/or modify it under the
* terms of the GNU General Public License as published by the Free Software
* Foundation; either version 2 of the License, or (at your option) any later
* version.
*
* Ingen is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
* FOR A PARTICULAR PURPOSE. See the GNU General Public License for details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include <sstream>
#include <lv2ext/lv2_event.h>
#include "Responder.hpp"
#include "SetPortValueEvent.hpp"
#include "Engine.hpp"
#include "PortImpl.hpp"
#include "ClientBroadcaster.hpp"
#include "NodeImpl.hpp"
#include "EngineStore.hpp"
#include "AudioBuffer.hpp"
#include "EventBuffer.hpp"
#include "ProcessContext.hpp"
#include "MessageContext.hpp"
using namespace std;
namespace Ingen {
/** Omni (all voices) control setting */
SetPortValueEvent::SetPortValueEvent(Engine& engine,
SharedPtr<Responder> responder,
bool queued,
SampleCount timestamp,
const string& port_path,
const Raul::Atom& value)
: QueuedEvent(engine, responder, timestamp)
, _queued(queued)
, _omni(true)
, _voice_num(0)
, _port_path(port_path)
, _value(value)
, _port(NULL)
, _error(NO_ERROR)
{
}
/** Voice-specific control setting */
SetPortValueEvent::SetPortValueEvent(Engine& engine,
SharedPtr<Responder> responder,
bool queued,
SampleCount timestamp,
uint32_t voice_num,
const string& port_path,
const Raul::Atom& value)
: QueuedEvent(engine, responder, timestamp)
, _queued(queued)
, _omni(false)
, _voice_num(voice_num)
, _port_path(port_path)
, _value(value)
, _port(NULL)
, _error(NO_ERROR)
{
}
SetPortValueEvent::~SetPortValueEvent()
{
}
void
SetPortValueEvent::pre_process()
{
if (_queued) {
if (_port == NULL) {
if (Path::is_valid(_port_path))
_port = _engine.engine_store()->find_port(_port_path);
else
_error = ILLEGAL_PATH;
}
if (_port == NULL && _error == NO_ERROR)
_error = PORT_NOT_FOUND;
}
// Port is a message context port, set its value and
// call the plugin's message run function once
if (_port && _port->context() == Context::MESSAGE) {
_engine.message_context()->run(_port->parent_node());
}
QueuedEvent::pre_process();
}
void
SetPortValueEvent::execute(ProcessContext& context)
{
Event::execute(context);
assert(_time >= context.start() && _time <= context.end());
if (_port && _port->context() == Context::MESSAGE)
return;
if (_error == NO_ERROR && _port == NULL) {
if (Path::is_valid(_port_path))
_port = _engine.engine_store()->find_port(_port_path);
else
_error = ILLEGAL_PATH;
}
if (_port == NULL) {
if (_error == NO_ERROR)
_error = PORT_NOT_FOUND;
/*} else if (_port->buffer(0)->capacity() < _data_size) {
_error = NO_SPACE;*/
} else {
Buffer* const buf = _port->buffer(0);
AudioBuffer* const abuf = dynamic_cast<AudioBuffer*>(buf);
if (abuf) {
if (_value.type() != Atom::FLOAT) {
_error = TYPE_MISMATCH;
return;
}
if (_omni) {
for (uint32_t i=0; i < _port->poly(); ++i)
((AudioBuffer*)_port->buffer(i))->set_value(
_value.get_float(), context.start(), _time);
} else {
if (_voice_num < _port->poly())
((AudioBuffer*)_port->buffer(_voice_num))->set_value(
_value.get_float(), context.start(), _time);
else
_error = ILLEGAL_VOICE;
}
return;
}
EventBuffer* const ebuf = dynamic_cast<EventBuffer*>(buf);
const LV2Features::Feature* f = _engine.world()->lv2_features->feature(LV2_URI_MAP_URI);
LV2URIMap* map = (LV2URIMap*)f->controller;
// FIXME: eliminate lookups
// FIXME: need a proper prefix system
if (ebuf && _value.type() == Atom::BLOB) {
const uint32_t frames = std::max(
(uint32_t)(_time - context.start()),
ebuf->latest_frames());
// Size 0 event, pass it along to the plugin as a typed but empty event
if (_value.data_size() == 0) {
cout << "BANG!" << endl;
const uint32_t type_id = map->uri_to_id(NULL, _value.get_blob_type());
ebuf->append(frames, 0, type_id, 0, NULL);
_port->raise_set_by_user_flag();
return;
} else if (!strcmp(_value.get_blob_type(), "lv2_midi:MidiEvent")) {
const uint32_t type_id = map->uri_to_id(NULL,
"http://lv2plug.in/ns/ext/midi#MidiEvent");
ebuf->prepare_write(context.start(), context.nframes());
// FIXME: use OSC midi type? avoid MIDI over OSC entirely?
ebuf->append(frames, 0, type_id, _value.data_size(),
(const uint8_t*)_value.get_blob());
_port->raise_set_by_user_flag();
return;
}
}
if (_value.type() == Atom::BLOB)
cerr << "WARNING: Unknown value blob type " << _value.get_blob_type() << endl;
else
cerr << "WARNING: Unknown value type " << (int)_value.type() << endl;
}
}
void
SetPortValueEvent::post_process()
{
if (_error == NO_ERROR) {
assert(_port != NULL);
_responder->respond_ok();
_engine.broadcaster()->send_port_value(_port_path, _value);
} else if (_error == ILLEGAL_PATH) {
string msg = "Illegal port path \"";
msg.append(_port_path).append("\"");
_responder->respond_error(msg);
} else if (_error == ILLEGAL_VOICE) {
std::ostringstream ss;
ss << "Illegal voice number " << _voice_num;
_responder->respond_error(ss.str());
} else if (_error == PORT_NOT_FOUND) {
string msg = "Unable to find port ";
msg.append(_port_path).append(" for set_port_value");
_responder->respond_error(msg);
} else if (_error == NO_SPACE) {
std::ostringstream msg("Attempt to write ");
msg << _value.data_size() << " bytes to " << _port_path << ", with capacity "
<< _port->buffer_size() << endl;
_responder->respond_error(msg.str());
}
}
} // namespace Ingen
<|endoftext|> |
<commit_before>/*
* The Apache Software License, Version 1.1
*
*
* Copyright (c) 1999 The Apache Software Foundation. All rights
* reserved.
*
* 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. The end-user documentation included with the redistribution,
* if any, must include the following acknowledgment:
* "This product includes software developed by the
* Apache Software Foundation (http://www.apache.org/)."
* Alternately, this acknowledgment may appear in the software itself,
* if and wherever such third-party acknowledgments normally appear.
*
* 4. The names "Xalan" and "Apache Software Foundation" must
* not be used to endorse or promote products derived from this
* software without prior written permission. For written
* permission, please contact apache@apache.org.
*
* 5. Products derived from this software may not be called "Apache",
* nor may "Apache" appear in their name, without prior written
* permission of the Apache Software Foundation.
*
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND ANY EXPRESSED 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 APACHE SOFTWARE FOUNDATION OR
* ITS 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.
* ====================================================================
*
* This software consists of voluntary contributions made by many
* individuals on behalf of the Apache Software Foundation and was
* originally based on software copyright (c) 1999, International
* Business Machines, Inc., http://www.ibm.com. For more
* information on the Apache Software Foundation, please see
* <http://www.apache.org/>.
*/
#if !defined(AIXDEFINITIONS_HEADER_GUARD_1357924680)
#define AIXDEFINITIONS_HEADER_GUARD_1357924680
// ---------------------------------------------------------------------------
// A define in the build for each project is also used to control whether
// the export keyword is from the project's viewpoint or the client's.
// These defines provide the platform specific keywords that they need
// to do this.
// ---------------------------------------------------------------------------
#define XALAN_PLATFORM_EXPORT
#define XALAN_PLATFORM_IMPORT
#define XALAN_PLATFORM_EXPORT_FUNCTION(T) T XALAN_PLATFORM_EXPORT
#define XALAN_PLATFORM_IMPORT_FUNCTION(T) T XALAN_PLATFORM_IMPORT
#define XALAN_OLD_STYLE_CASTS
#define XALAN_OLD_STREAMS
#define XALAN_NO_NAMESPACES
#define XALAN_NO_MUTABLE
#define XALAN_SGI_BASED_STL
#define XALAN_NO_MEMBER_TEMPLATES
#define XALAN_AMBIGUOUS_EVEN_IF_NOT_CALLED
#define XALAN_CANNOT_DELETE_CONST
#define XALAN_BOOL_AS_INT
#define XALAN_NO_STD_ALLOCATORS
#define XALAN_NO_SELECTIVE_TEMPLATE_INSTANTIATION
#define XALAN_NO_ALGORITHMS_WITH_BUILTINS
#define XALAN_NO_DEFAULT_TEMPLATE_ARGUMENTS
#define XALAN_NO_COVARIANT_RETURN_TYPE
#define XALAN_LSTRSUPPORT
#define XALAN_AUTO_PTR_REQUIRES_DEFINITION
#define XALAN_NEEDS_EXPLICIT_TEMPLATE_INSTANTIATION
#define XALAN_XALANDOMCHAR_USHORT_MISMATCH
#define XALAN_BIG_ENDIAN
#define XALAN_STLPORT_STL
#define XALAN_TEMPLATE_FUNCTION_NO_DEFAULT_PARAMETERS
#define XALAN_USE_WCHAR_CAST_HACK
#define XALAN_POSIX2_AVAILABLE
#define XALAN_UNALIGNED
// STL Port Definitions
#define __STL_NO_SGI_IOSTREAMS
#include <stl/_config.h>
#endif // AIXDEFINITIONS_HEADER_GUARD_1357924680
<commit_msg>Change for xlC 5.02<commit_after>/*
* The Apache Software License, Version 1.1
*
*
* Copyright (c) 1999 The Apache Software Foundation. All rights
* reserved.
*
* 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. The end-user documentation included with the redistribution,
* if any, must include the following acknowledgment:
* "This product includes software developed by the
* Apache Software Foundation (http://www.apache.org/)."
* Alternately, this acknowledgment may appear in the software itself,
* if and wherever such third-party acknowledgments normally appear.
*
* 4. The names "Xalan" and "Apache Software Foundation" must
* not be used to endorse or promote products derived from this
* software without prior written permission. For written
* permission, please contact apache@apache.org.
*
* 5. Products derived from this software may not be called "Apache",
* nor may "Apache" appear in their name, without prior written
* permission of the Apache Software Foundation.
*
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND ANY EXPRESSED 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 APACHE SOFTWARE FOUNDATION OR
* ITS 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.
* ====================================================================
*
* This software consists of voluntary contributions made by many
* individuals on behalf of the Apache Software Foundation and was
* originally based on software copyright (c) 1999, International
* Business Machines, Inc., http://www.ibm.com. For more
* information on the Apache Software Foundation, please see
* <http://www.apache.org/>.
*/
#if !defined(AIXDEFINITIONS_HEADER_GUARD_1357924680)
#define AIXDEFINITIONS_HEADER_GUARD_1357924680
// ---------------------------------------------------------------------------
// A define in the build for each project is also used to control whether
// the export keyword is from the project's viewpoint or the client's.
// These defines provide the platform specific keywords that they need
// to do this.
// ---------------------------------------------------------------------------
#define XALAN_PLATFORM_EXPORT
#define XALAN_PLATFORM_IMPORT
#define XALAN_PLATFORM_EXPORT_FUNCTION(T) T XALAN_PLATFORM_EXPORT
#define XALAN_PLATFORM_IMPORT_FUNCTION(T) T XALAN_PLATFORM_IMPORT
#define XALAN_LSTRSUPPORT
#define XALAN_USE_WCHAR_CAST_HACK
#define XALAN_POSIX2_AVAILABLE
#define XALAN_BIG_ENDIAN
#define XALAN_XALANDOMCHAR_USHORT_MISMATCH
#if __IBMCPP__ >= 4
#define XALAN_EXPLICIT_SCOPE_IN_TEMPLATE_BUG
#define XALAN_NEW_STD_ALLOCATOR
#else
#define XALAN_OLD_STYLE_CASTS
#define XALAN_OLD_STREAMS
#define XALAN_NO_NAMESPACES
#define XALAN_NO_MUTABLE
#define XALAN_SGI_BASED_STL
#define XALAN_NO_MEMBER_TEMPLATES
#define XALAN_AMBIGUOUS_EVEN_IF_NOT_CALLED
#define XALAN_CANNOT_DELETE_CONST
#define XALAN_BOOL_AS_INT
#define XALAN_NO_STD_ALLOCATORS
#define XALAN_NO_SELECTIVE_TEMPLATE_INSTANTIATION
#define XALAN_NO_ALGORITHMS_WITH_BUILTINS
#define XALAN_NO_DEFAULT_TEMPLATE_ARGUMENTS
#define XALAN_NO_COVARIANT_RETURN_TYPE
#define XALAN_AUTO_PTR_REQUIRES_DEFINITION
#define XALAN_NEEDS_EXPLICIT_TEMPLATE_INSTANTIATION
#define XALAN_STLPORT_STL
#define XALAN_TEMPLATE_FUNCTION_NO_DEFAULT_PARAMETERS
// STL Port Definitions
#define __STL_NO_SGI_IOSTREAMS
#include <stl/_config.h>
#endif
#define XALAN_UNALIGNED
#endif // AIXDEFINITIONS_HEADER_GUARD_1357924680
<|endoftext|> |
<commit_before>// Copyright (c) 2006-2008 The Chromium Authors. All rights reserved.
// Use of this source code is governed by a BSD-style license that can be
// found in the LICENSE file.
#include <string>
#include "base/logging.h"
#include "base/mime_util.h"
#include "net/base/platform_mime_util.h"
namespace net {
bool PlatformMimeUtil::GetPlatformMimeTypeFromExtension(
const FilePath::StringType& ext, std::string* result) const {
FilePath::StringType dummy_path = "foo." + ext;
std::string out = mime_util::GetFileMimeType(dummy_path);
// GetFileMimeType likes to return application/octet-stream
// for everything it doesn't know - ignore that.
if (out == "application/octet-stream" || !out.length())
return false;
*result = out;
return true;
}
bool PlatformMimeUtil::GetPreferredExtensionForMimeType(
const std::string& mime_type, FilePath::StringType* ext) const {
// Unlike GetPlatformMimeTypeFromExtension, this method doesn't have a
// default list that it uses, but for now we are also returning false since
// this doesn't really matter as much under Linux.
//
// If we wanted to do this properly, we would read the mime.cache file which
// has a section where they assign a glob (*.gif) to a mimetype
// (image/gif). We look up the "heaviest" glob for a certain mime type and
// then then try to chop off "*.".
NOTIMPLEMENTED();
return false;
}
} // namespace net
<commit_msg>Override .ico file's mime type on Linux. XDG's mime database has a bogus "image/x-ico" entry whereas the rest of the world uses "image/x-icon".<commit_after>// Copyright (c) 2006-2008 The Chromium Authors. All rights reserved.
// Use of this source code is governed by a BSD-style license that can be
// found in the LICENSE file.
#include <string>
#include "base/logging.h"
#include "base/mime_util.h"
#include "net/base/platform_mime_util.h"
namespace net {
bool PlatformMimeUtil::GetPlatformMimeTypeFromExtension(
const FilePath::StringType& ext, std::string* result) const {
FilePath::StringType dummy_path = "foo." + ext;
std::string out = mime_util::GetFileMimeType(dummy_path);
// GetFileMimeType likes to return application/octet-stream
// for everything it doesn't know - ignore that.
if (out == "application/octet-stream" || !out.length())
return false;
// GetFileMimeType returns image/x-ico because that's what's in the XDG
// mime database. That database is the merger of the Gnome and KDE mime
// databases. Apparently someone working on KDE in 2001 decided .ico
// resolves to image/x-ico, whereas the rest of the world uses image/x-icon.
// FWIW, image/vnd.microsoft.icon is the official IANA assignment.
if (out == "image/x-ico")
out = "image/x-icon";
*result = out;
return true;
}
bool PlatformMimeUtil::GetPreferredExtensionForMimeType(
const std::string& mime_type, FilePath::StringType* ext) const {
// Unlike GetPlatformMimeTypeFromExtension, this method doesn't have a
// default list that it uses, but for now we are also returning false since
// this doesn't really matter as much under Linux.
//
// If we wanted to do this properly, we would read the mime.cache file which
// has a section where they assign a glob (*.gif) to a mimetype
// (image/gif). We look up the "heaviest" glob for a certain mime type and
// then then try to chop off "*.".
NOTIMPLEMENTED();
return false;
}
} // namespace net
<|endoftext|> |
<commit_before>/*
Copyright (C) 2013 Martin Klapetek <mklapetek@kde.org>
Copyright (C) 2014 David Edmundson <davidedmundson@kde.org>
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "im-persons-data-source.h"
#include <TelepathyQt/AccountManager>
#include <TelepathyQt/AccountFactory>
#include <TelepathyQt/ContactManager>
#include <TelepathyQt/PendingOperation>
#include <TelepathyQt/PendingReady>
#include <TelepathyQt/Presence>
#include "KTp/contact-factory.h"
#include "KTp/global-contact-manager.h"
#include "KTp/types.h"
#include <KPeople/AllContactsMonitor>
#include <KDE/KABC/Addressee>
#include <KDebug>
#include <KGlobal>
#include <KStandardDirs>
#include <KPluginFactory>
#include <KPluginLoader>
#include <QSqlDatabase>
#include <QSqlQuery>
using namespace KPeople;
class KTpAllContacts : public AllContactsMonitor
{
Q_OBJECT
public:
KTpAllContacts();
~KTpAllContacts();
virtual KABC::Addressee::Map contacts();
private Q_SLOTS:
void loadCache();
void onAccountManagerReady(Tp::PendingOperation *op);
void onContactChanged();
void onContactInvalidated();
void onAllKnownContactsChanged(const Tp::Contacts &contactsAdded, const Tp::Contacts &contactsRemoved);
private:
QString createUri(const KTp::ContactPtr &contact) const;
KABC::Addressee contactToAddressee(const Tp::ContactPtr &contact) const;
//presence names indexed by ConnectionPresenceType
QVector<QString> m_presenceStrings;
QHash<QString, KTp::ContactPtr> m_contacts;
KABC::Addressee::Map m_contactVCards;
};
KTpAllContacts::KTpAllContacts()
{
Tp::registerTypes();
m_presenceStrings.reserve(9);
m_presenceStrings.insert(Tp::ConnectionPresenceTypeUnset, QString());
m_presenceStrings.insert(Tp::ConnectionPresenceTypeOffline, QString::fromLatin1("offline"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeAvailable, QString::fromLatin1("available"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeAway, QString::fromLatin1("away"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeExtendedAway, QString::fromLatin1("xa"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeHidden, QString::fromLatin1("hidden")); //of 'offline' ?
m_presenceStrings.insert(Tp::ConnectionPresenceTypeBusy, QString::fromLatin1("busy"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeUnknown, QString());
m_presenceStrings.insert(Tp::ConnectionPresenceTypeError, QString());
loadCache();
}
KTpAllContacts::~KTpAllContacts()
{
}
void KTpAllContacts::loadCache()
{
QSqlDatabase db = QSqlDatabase::addDatabase(QLatin1String("QSQLITE"), QLatin1String("ktpCache"));
db.setDatabaseName(KGlobal::dirs()->locateLocal("data", QLatin1String("ktp/cache.db")));
db.open();
QSqlQuery query(db);
query.exec(QLatin1String("SELECT groupName FROM groups ORDER BY groupId;"));
QStringList groupsList;
while (query.next()) {
groupsList.append(query.value(0).toString());
}
if (!groupsList.isEmpty()) {
query.exec(QLatin1String("SELECT accountId, contactId, alias, avatarFileName, groupsIds FROM contacts;"));
} else {
query.exec(QLatin1String("SELECT accountId, contactId, alias, avatarFileName FROM contacts;"));
}
while (query.next()) {
KABC::Addressee addressee;
const QString accountId = query.value(0).toString();
const QString contactId = query.value(1).toString();
addressee.setFormattedName(query.value(2).toString());
addressee.setPhoto(KABC::Picture(query.value(3).toString()));
if (!groupsList.isEmpty()) {
QStringList contactGroups;
Q_FOREACH (const QString &groupIdStr, query.value(4).toString().split(QLatin1String(","))) {
bool convSuccess;
int groupId = groupIdStr.toInt(&convSuccess);
if ((!convSuccess) || (groupId >= groupsList.count()))
continue;
contactGroups.append(groupsList.at(groupId));
}
addressee.setCategories(contactGroups);
}
addressee.insertCustom(QLatin1String("telepathy"), QLatin1String("contactId"), contactId);
addressee.insertCustom(QLatin1String("telepathy"), QLatin1String("accountPath"), accountId);
addressee.insertCustom(QLatin1String("telepathy"), QLatin1String("presence"), QLatin1String("offline"));
const QString uri = QLatin1String("ktp://") + accountId + QLatin1Char('?') + contactId;
m_contactVCards[uri] = addressee;
Q_EMIT contactAdded(uri, addressee);
}
//now start fetching the up-to-date information
connect(KTp::accountManager()->becomeReady(), SIGNAL(finished(Tp::PendingOperation*)),
this, SLOT(onAccountManagerReady(Tp::PendingOperation*)));
emitInitialFetchComplete();
}
QString KTpAllContacts::createUri(const KTp::ContactPtr &contact) const
{
// so real ID will look like
// ktp://gabble/jabber/blah/asdfjwer?foo@bar.com
// ? is used as it is not a valid character in the dbus path that makes up the account UID
return QLatin1String("ktp://") + contact->accountUniqueIdentifier() + QLatin1Char('?') + contact->id();
}
void KTpAllContacts::onAccountManagerReady(Tp::PendingOperation *op)
{
if (op->isError()) {
kWarning() << "Failed to initialize AccountManager:" << op->errorName();
kWarning() << op->errorMessage();
return;
}
kDebug() << "Account manager ready";
connect(KTp::contactManager(), SIGNAL(allKnownContactsChanged(Tp::Contacts,Tp::Contacts)),
this, SLOT(onAllKnownContactsChanged(Tp::Contacts,Tp::Contacts)));
onAllKnownContactsChanged(KTp::contactManager()->allKnownContacts(), Tp::Contacts());
}
void KTpAllContacts::onAllKnownContactsChanged(const Tp::Contacts &contactsAdded, const Tp::Contacts &contactsRemoved)
{
if (!m_contacts.isEmpty()) {
Q_FOREACH (const Tp::ContactPtr &c, contactsRemoved) {
const KTp::ContactPtr &contact = KTp::ContactPtr::qObjectCast(c);
const QString uri = createUri(contact);
m_contacts.remove(uri);
m_contactVCards.remove(uri);
Q_EMIT contactRemoved(uri);
}
}
Q_FOREACH (const Tp::ContactPtr &contact, contactsAdded) {
KTp::ContactPtr ktpContact = KTp::ContactPtr::qObjectCast(contact);
const QString uri = createUri(ktpContact);
const KABC::Addressee vcard = contactToAddressee(contact);
m_contacts.insert(uri, ktpContact);
//TODO OPTIMISATION if we already exist we shouldn't create a whole new KABC object, just update the existing one
//onContactChanged should be split into the relevant onAliasChanged etc.
if (m_contactVCards.contains(uri)) {
m_contactVCards[uri] = vcard;
Q_EMIT contactChanged(uri, vcard);
} else {
m_contactVCards.insert(uri, vcard);
Q_EMIT contactAdded(uri, vcard);
}
connect(ktpContact.data(), SIGNAL(presenceChanged(Tp::Presence)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(capabilitiesChanged(Tp::ContactCapabilities)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(invalidated()),
this, SLOT(onContactInvalidated()));
connect(ktpContact.data(), SIGNAL(avatarDataChanged(Tp::AvatarData)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(addedToGroup(QString)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(removedFromGroup(QString)),
this, SLOT(onContactChanged()));
}
}
void KTpAllContacts::onContactChanged()
{
const KTp::ContactPtr contact(qobject_cast<KTp::Contact*>(sender()));
m_contactVCards.insert(createUri(contact), contactToAddressee(contact));
Q_EMIT contactChanged(createUri(contact), contactToAddressee(contact));
}
void KTpAllContacts::onContactInvalidated()
{
const KTp::ContactPtr contact(qobject_cast<KTp::Contact*>(sender()));
const QString uri = createUri(contact);
m_contacts.remove(uri);
//set to offline and emit changed
KABC::Addressee &vcard = m_contactVCards[uri];
vcard.insertCustom(QLatin1String("telepathy"), QLatin1String("presence"), QLatin1String("offline"));
Q_EMIT contactChanged(uri, vcard);
}
KABC::Addressee::Map KTpAllContacts::contacts()
{
return m_contactVCards;
}
KABC::Addressee KTpAllContacts::contactToAddressee(const Tp::ContactPtr &contact) const
{
KABC::Addressee vcard;
Tp::AccountPtr account = KTp::contactManager()->accountForContact(contact);
if (contact && account) {
vcard.setFormattedName(contact->alias());
vcard.setCategories(contact->groups());
//TODO make "telepathy" a member variable string so that we ref count the same object instead of making new strings
vcard.insertCustom(QLatin1String("telepathy"), QLatin1String("contactId"), contact->id());
vcard.insertCustom(QLatin1String("telepathy"), QLatin1String("accountPath"), account->objectPath());
vcard.insertCustom(QLatin1String("telepathy"), QLatin1String("presence"), m_presenceStrings.at(contact->presence().type()));
if (!contact->avatarData().fileName.isEmpty()) {
vcard.setPhoto(KABC::Picture(contact->avatarData().fileName));
}
}
return vcard;
}
IMPersonsDataSource::IMPersonsDataSource(QObject *parent, const QVariantList &args)
: BasePersonsDataSource(parent)
{
Q_UNUSED(args);
}
IMPersonsDataSource::~IMPersonsDataSource()
{
}
QString IMPersonsDataSource::sourcePluginId() const
{
return QLatin1String("ktp");
}
AllContactsMonitor* IMPersonsDataSource::createAllContactsMonitor()
{
return new KTpAllContacts();
}
K_PLUGIN_FACTORY( IMPersonsDataSourceFactory, registerPlugin<IMPersonsDataSource>(); )
K_EXPORT_PLUGIN( IMPersonsDataSourceFactory("im_persons_data_source_plugin") )
#include "im-persons-data-source.moc"
<commit_msg>Share the same QString for all KABC Custom fields<commit_after>/*
Copyright (C) 2013 Martin Klapetek <mklapetek@kde.org>
Copyright (C) 2014 David Edmundson <davidedmundson@kde.org>
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "im-persons-data-source.h"
#include <TelepathyQt/AccountManager>
#include <TelepathyQt/AccountFactory>
#include <TelepathyQt/ContactManager>
#include <TelepathyQt/PendingOperation>
#include <TelepathyQt/PendingReady>
#include <TelepathyQt/Presence>
#include "KTp/contact-factory.h"
#include "KTp/global-contact-manager.h"
#include "KTp/types.h"
#include <KPeople/AllContactsMonitor>
#include <KDE/KABC/Addressee>
#include <KDebug>
#include <KGlobal>
#include <KStandardDirs>
#include <KPluginFactory>
#include <KPluginLoader>
#include <QSqlDatabase>
#include <QSqlQuery>
using namespace KPeople;
class KTpAllContacts : public AllContactsMonitor
{
Q_OBJECT
public:
KTpAllContacts();
~KTpAllContacts();
virtual KABC::Addressee::Map contacts();
private Q_SLOTS:
void loadCache();
void onAccountManagerReady(Tp::PendingOperation *op);
void onContactChanged();
void onContactInvalidated();
void onAllKnownContactsChanged(const Tp::Contacts &contactsAdded, const Tp::Contacts &contactsRemoved);
private:
QString createUri(const KTp::ContactPtr &contact) const;
KABC::Addressee contactToAddressee(const Tp::ContactPtr &contact) const;
//presence names indexed by ConnectionPresenceType
QVector<QString> m_presenceStrings;
QHash<QString, KTp::ContactPtr> m_contacts;
KABC::Addressee::Map m_contactVCards;
};
static const QString S_KABC_PRODUCT = QString::fromLatin1("telepathy");
static const QString S_KABC_FIELD_ACCOUNT_PATH = QString::fromLatin1("accountPath");
static const QString S_KABC_FIELD_CONTACT_ID = QString::fromLatin1("contactId");
static const QString S_KABC_FIELD_PRESENCE = QString::fromLatin1("presence");
KTpAllContacts::KTpAllContacts()
{
Tp::registerTypes();
m_presenceStrings.reserve(9);
m_presenceStrings.insert(Tp::ConnectionPresenceTypeUnset, QString());
m_presenceStrings.insert(Tp::ConnectionPresenceTypeOffline, QString::fromLatin1("offline"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeAvailable, QString::fromLatin1("available"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeAway, QString::fromLatin1("away"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeExtendedAway, QString::fromLatin1("xa"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeHidden, QString::fromLatin1("hidden")); //of 'offline' ?
m_presenceStrings.insert(Tp::ConnectionPresenceTypeBusy, QString::fromLatin1("busy"));
m_presenceStrings.insert(Tp::ConnectionPresenceTypeUnknown, QString());
m_presenceStrings.insert(Tp::ConnectionPresenceTypeError, QString());
loadCache();
}
KTpAllContacts::~KTpAllContacts()
{
}
void KTpAllContacts::loadCache()
{
QSqlDatabase db = QSqlDatabase::addDatabase(QLatin1String("QSQLITE"), QLatin1String("ktpCache"));
db.setDatabaseName(KGlobal::dirs()->locateLocal("data", QLatin1String("ktp/cache.db")));
db.open();
QSqlQuery query(db);
query.exec(QLatin1String("SELECT groupName FROM groups ORDER BY groupId;"));
QStringList groupsList;
while (query.next()) {
groupsList.append(query.value(0).toString());
}
if (!groupsList.isEmpty()) {
query.exec(QLatin1String("SELECT accountId, contactId, alias, avatarFileName, groupsIds FROM contacts;"));
} else {
query.exec(QLatin1String("SELECT accountId, contactId, alias, avatarFileName FROM contacts;"));
}
while (query.next()) {
KABC::Addressee addressee;
const QString accountId = query.value(0).toString();
const QString contactId = query.value(1).toString();
addressee.setFormattedName(query.value(2).toString());
addressee.setPhoto(KABC::Picture(query.value(3).toString()));
if (!groupsList.isEmpty()) {
QStringList contactGroups;
Q_FOREACH (const QString &groupIdStr, query.value(4).toString().split(QLatin1String(","))) {
bool convSuccess;
int groupId = groupIdStr.toInt(&convSuccess);
if ((!convSuccess) || (groupId >= groupsList.count()))
continue;
contactGroups.append(groupsList.at(groupId));
}
addressee.setCategories(contactGroups);
}
addressee.insertCustom(S_KABC_PRODUCT, S_KABC_FIELD_CONTACT_ID, contactId);
addressee.insertCustom(S_KABC_PRODUCT, S_KABC_FIELD_ACCOUNT_PATH, accountId);
addressee.insertCustom(S_KABC_PRODUCT, S_KABC_FIELD_PRESENCE, m_presenceStrings.at(Tp::ConnectionPresenceTypeOffline));
const QString uri = QLatin1String("ktp://") + accountId + QLatin1Char('?') + contactId;
m_contactVCards[uri] = addressee;
Q_EMIT contactAdded(uri, addressee);
}
//now start fetching the up-to-date information
connect(KTp::accountManager()->becomeReady(), SIGNAL(finished(Tp::PendingOperation*)),
this, SLOT(onAccountManagerReady(Tp::PendingOperation*)));
emitInitialFetchComplete();
}
QString KTpAllContacts::createUri(const KTp::ContactPtr &contact) const
{
// so real ID will look like
// ktp://gabble/jabber/blah/asdfjwer?foo@bar.com
// ? is used as it is not a valid character in the dbus path that makes up the account UID
return QLatin1String("ktp://") + contact->accountUniqueIdentifier() + QLatin1Char('?') + contact->id();
}
void KTpAllContacts::onAccountManagerReady(Tp::PendingOperation *op)
{
if (op->isError()) {
kWarning() << "Failed to initialize AccountManager:" << op->errorName();
kWarning() << op->errorMessage();
return;
}
kDebug() << "Account manager ready";
connect(KTp::contactManager(), SIGNAL(allKnownContactsChanged(Tp::Contacts,Tp::Contacts)),
this, SLOT(onAllKnownContactsChanged(Tp::Contacts,Tp::Contacts)));
onAllKnownContactsChanged(KTp::contactManager()->allKnownContacts(), Tp::Contacts());
}
void KTpAllContacts::onAllKnownContactsChanged(const Tp::Contacts &contactsAdded, const Tp::Contacts &contactsRemoved)
{
if (!m_contacts.isEmpty()) {
Q_FOREACH (const Tp::ContactPtr &c, contactsRemoved) {
const KTp::ContactPtr &contact = KTp::ContactPtr::qObjectCast(c);
const QString uri = createUri(contact);
m_contacts.remove(uri);
m_contactVCards.remove(uri);
Q_EMIT contactRemoved(uri);
}
}
Q_FOREACH (const Tp::ContactPtr &contact, contactsAdded) {
KTp::ContactPtr ktpContact = KTp::ContactPtr::qObjectCast(contact);
const QString uri = createUri(ktpContact);
const KABC::Addressee vcard = contactToAddressee(contact);
m_contacts.insert(uri, ktpContact);
//TODO OPTIMISATION if we already exist we shouldn't create a whole new KABC object, just update the existing one
//onContactChanged should be split into the relevant onAliasChanged etc.
if (m_contactVCards.contains(uri)) {
m_contactVCards[uri] = vcard;
Q_EMIT contactChanged(uri, vcard);
} else {
m_contactVCards.insert(uri, vcard);
Q_EMIT contactAdded(uri, vcard);
}
connect(ktpContact.data(), SIGNAL(presenceChanged(Tp::Presence)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(capabilitiesChanged(Tp::ContactCapabilities)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(invalidated()),
this, SLOT(onContactInvalidated()));
connect(ktpContact.data(), SIGNAL(avatarDataChanged(Tp::AvatarData)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(addedToGroup(QString)),
this, SLOT(onContactChanged()));
connect(ktpContact.data(), SIGNAL(removedFromGroup(QString)),
this, SLOT(onContactChanged()));
}
}
void KTpAllContacts::onContactChanged()
{
const KTp::ContactPtr contact(qobject_cast<KTp::Contact*>(sender()));
m_contactVCards.insert(createUri(contact), contactToAddressee(contact));
Q_EMIT contactChanged(createUri(contact), contactToAddressee(contact));
}
void KTpAllContacts::onContactInvalidated()
{
const KTp::ContactPtr contact(qobject_cast<KTp::Contact*>(sender()));
const QString uri = createUri(contact);
m_contacts.remove(uri);
//set to offline and emit changed
KABC::Addressee &vcard = m_contactVCards[uri];
vcard.insertCustom(S_KABC_PRODUCT, S_KABC_FIELD_PRESENCE, QLatin1String("offline"));
Q_EMIT contactChanged(uri, vcard);
}
KABC::Addressee::Map KTpAllContacts::contacts()
{
return m_contactVCards;
}
KABC::Addressee KTpAllContacts::contactToAddressee(const Tp::ContactPtr &contact) const
{
KABC::Addressee vcard;
Tp::AccountPtr account = KTp::contactManager()->accountForContact(contact);
if (contact && account) {
vcard.setFormattedName(contact->alias());
vcard.setCategories(contact->groups());
vcard.insertCustom(S_KABC_PRODUCT, S_KABC_FIELD_CONTACT_ID, contact->id());
vcard.insertCustom(S_KABC_PRODUCT, S_KABC_FIELD_ACCOUNT_PATH, account->objectPath());
vcard.insertCustom(S_KABC_PRODUCT, S_KABC_FIELD_PRESENCE, m_presenceStrings.at(contact->presence().type()));
if (!contact->avatarData().fileName.isEmpty()) {
vcard.setPhoto(KABC::Picture(contact->avatarData().fileName));
}
}
return vcard;
}
IMPersonsDataSource::IMPersonsDataSource(QObject *parent, const QVariantList &args)
: BasePersonsDataSource(parent)
{
Q_UNUSED(args);
}
IMPersonsDataSource::~IMPersonsDataSource()
{
}
QString IMPersonsDataSource::sourcePluginId() const
{
return QLatin1String("ktp");
}
AllContactsMonitor* IMPersonsDataSource::createAllContactsMonitor()
{
return new KTpAllContacts();
}
K_PLUGIN_FACTORY( IMPersonsDataSourceFactory, registerPlugin<IMPersonsDataSource>(); )
K_EXPORT_PLUGIN( IMPersonsDataSourceFactory("im_persons_data_source_plugin") )
#include "im-persons-data-source.moc"
<|endoftext|> |
<commit_before>// Copyright (c) 2009 The Chromium Authors. All rights reserved.
// Use of this source code is governed by a BSD-style license that can be
// found in the LICENSE file.
#include "net/base/transport_security_state.h"
#include "base/base64.h"
#include "base/json/json_reader.h"
#include "base/json/json_writer.h"
#include "base/logging.h"
#include "base/scoped_ptr.h"
#include "base/sha2.h"
#include "base/string_tokenizer.h"
#include "base/string_util.h"
#include "base/values.h"
#include "googleurl/src/gurl.h"
#include "net/base/dns_util.h"
namespace net {
TransportSecurityState::TransportSecurityState()
: delegate_(NULL) {
}
void TransportSecurityState::EnableHost(const std::string& host,
const DomainState& state) {
const std::string canonicalised_host = CanonicaliseHost(host);
if (canonicalised_host.empty())
return;
bool temp;
if (isPreloadedSTS(canonicalised_host, &temp))
return;
char hashed[base::SHA256_LENGTH];
base::SHA256HashString(canonicalised_host, hashed, sizeof(hashed));
// Use the original creation date if we already have this host.
DomainState state_copy(state);
DomainState existing_state;
if (IsEnabledForHost(&existing_state, host))
state_copy.created = existing_state.created;
enabled_hosts_[std::string(hashed, sizeof(hashed))] = state_copy;
DirtyNotify();
}
bool TransportSecurityState::IsEnabledForHost(DomainState* result,
const std::string& host) {
const std::string canonicalised_host = CanonicaliseHost(host);
if (canonicalised_host.empty())
return false;
bool include_subdomains;
if (isPreloadedSTS(canonicalised_host, &include_subdomains)) {
result->created = result->expiry = base::Time::FromTimeT(0);
result->mode = DomainState::MODE_STRICT;
result->include_subdomains = include_subdomains;
return true;
}
base::Time current_time(base::Time::Now());
for (size_t i = 0; canonicalised_host[i]; i += canonicalised_host[i] + 1) {
char hashed_domain[base::SHA256_LENGTH];
base::SHA256HashString(&canonicalised_host[i], &hashed_domain,
sizeof(hashed_domain));
std::map<std::string, DomainState>::iterator j =
enabled_hosts_.find(std::string(hashed_domain, sizeof(hashed_domain)));
if (j == enabled_hosts_.end())
continue;
if (current_time > j->second.expiry) {
enabled_hosts_.erase(j);
DirtyNotify();
continue;
}
*result = j->second;
// If we matched the domain exactly, it doesn't matter what the value of
// include_subdomains is.
if (i == 0)
return true;
return j->second.include_subdomains;
}
return false;
}
// "Strict-Transport-Security" ":"
// "max-age" "=" delta-seconds [ ";" "includeSubDomains" ]
bool TransportSecurityState::ParseHeader(const std::string& value,
int* max_age,
bool* include_subdomains) {
DCHECK(max_age);
DCHECK(include_subdomains);
int max_age_candidate;
enum ParserState {
START,
AFTER_MAX_AGE_LABEL,
AFTER_MAX_AGE_EQUALS,
AFTER_MAX_AGE,
AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER,
AFTER_INCLUDE_SUBDOMAINS,
} state = START;
StringTokenizer tokenizer(value, " \t=;");
tokenizer.set_options(StringTokenizer::RETURN_DELIMS);
while (tokenizer.GetNext()) {
DCHECK(!tokenizer.token_is_delim() || tokenizer.token().length() == 1);
switch (state) {
case START:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (!LowerCaseEqualsASCII(tokenizer.token(), "max-age"))
return false;
state = AFTER_MAX_AGE_LABEL;
break;
case AFTER_MAX_AGE_LABEL:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (*tokenizer.token_begin() != '=')
return false;
DCHECK(tokenizer.token().length() == 1);
state = AFTER_MAX_AGE_EQUALS;
break;
case AFTER_MAX_AGE_EQUALS:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (!StringToInt(tokenizer.token(), &max_age_candidate))
return false;
if (max_age_candidate < 0)
return false;
state = AFTER_MAX_AGE;
break;
case AFTER_MAX_AGE:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (*tokenizer.token_begin() != ';')
return false;
state = AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER;
break;
case AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (!LowerCaseEqualsASCII(tokenizer.token(), "includesubdomains"))
return false;
state = AFTER_INCLUDE_SUBDOMAINS;
break;
case AFTER_INCLUDE_SUBDOMAINS:
if (!IsAsciiWhitespace(*tokenizer.token_begin()))
return false;
break;
default:
NOTREACHED();
}
}
// We've consumed all the input. Let's see what state we ended up in.
switch (state) {
case START:
case AFTER_MAX_AGE_LABEL:
case AFTER_MAX_AGE_EQUALS:
return false;
case AFTER_MAX_AGE:
*max_age = max_age_candidate;
*include_subdomains = false;
return true;
case AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER:
return false;
case AFTER_INCLUDE_SUBDOMAINS:
*max_age = max_age_candidate;
*include_subdomains = true;
return true;
default:
NOTREACHED();
return false;
}
}
void TransportSecurityState::SetDelegate(
TransportSecurityState::Delegate* delegate) {
delegate_ = delegate;
}
// This function converts the binary hashes, which we store in
// |enabled_hosts_|, to a base64 string which we can include in a JSON file.
static std::wstring HashedDomainToExternalString(const std::string& hashed) {
std::string out;
CHECK(base::Base64Encode(hashed, &out));
return ASCIIToWide(out);
}
// This inverts |HashedDomainToExternalString|, above. It turns an external
// string (from a JSON file) into an internal (binary) string.
static std::string ExternalStringToHashedDomain(const std::wstring& external) {
std::string external_ascii = WideToASCII(external);
std::string out;
if (!base::Base64Decode(external_ascii, &out) ||
out.size() != base::SHA256_LENGTH) {
return std::string();
}
return out;
}
bool TransportSecurityState::Serialise(std::string* output) {
DictionaryValue toplevel;
for (std::map<std::string, DomainState>::const_iterator
i = enabled_hosts_.begin(); i != enabled_hosts_.end(); ++i) {
DictionaryValue* state = new DictionaryValue;
state->SetBoolean(L"include_subdomains", i->second.include_subdomains);
state->SetReal(L"created", i->second.created.ToDoubleT());
state->SetReal(L"expiry", i->second.expiry.ToDoubleT());
switch (i->second.mode) {
case DomainState::MODE_STRICT:
state->SetString(L"mode", "strict");
break;
case DomainState::MODE_OPPORTUNISTIC:
state->SetString(L"mode", "opportunistic");
break;
case DomainState::MODE_SPDY_ONLY:
state->SetString(L"mode", "spdy-only");
break;
default:
NOTREACHED() << "DomainState with unknown mode";
delete state;
continue;
}
toplevel.Set(HashedDomainToExternalString(i->first), state);
}
base::JSONWriter::Write(&toplevel, true /* pretty print */, output);
return true;
}
bool TransportSecurityState::Deserialise(const std::string& input,
bool* dirty) {
enabled_hosts_.clear();
scoped_ptr<Value> value(
base::JSONReader::Read(input, false /* do not allow trailing commas */));
if (!value.get() || !value->IsType(Value::TYPE_DICTIONARY))
return false;
DictionaryValue* dict_value = reinterpret_cast<DictionaryValue*>(value.get());
const base::Time current_time(base::Time::Now());
bool dirtied = false;
for (DictionaryValue::key_iterator i = dict_value->begin_keys();
i != dict_value->end_keys(); ++i) {
DictionaryValue* state;
if (!dict_value->GetDictionaryWithoutPathExpansion(*i, &state))
continue;
bool include_subdomains;
std::string mode_string;
double created;
double expiry;
if (!state->GetBoolean(L"include_subdomains", &include_subdomains) ||
!state->GetString(L"mode", &mode_string) ||
!state->GetReal(L"expiry", &expiry)) {
continue;
}
DomainState::Mode mode;
if (mode_string == "strict") {
mode = DomainState::MODE_STRICT;
} else if (mode_string == "opportunistic") {
mode = DomainState::MODE_OPPORTUNISTIC;
} else if (mode_string == "spdy-only") {
mode = DomainState::MODE_SPDY_ONLY;
} else {
LOG(WARNING) << "Unknown TransportSecurityState mode string found: "
<< mode_string;
continue;
}
base::Time expiry_time = base::Time::FromDoubleT(expiry);
base::Time created_time;
if (state->GetReal(L"created", &created)) {
created_time = base::Time::FromDoubleT(created);
} else {
// We're migrating an old entry with no creation date. Make sure we
// write the new date back in a reasonable time frame.
dirtied = true;
created_time = base::Time::Now();
}
if (expiry_time <= current_time) {
// Make sure we dirty the state if we drop an entry.
dirtied = true;
continue;
}
std::string hashed = ExternalStringToHashedDomain(*i);
if (hashed.empty())
continue;
DomainState new_state;
new_state.mode = mode;
new_state.created = created_time;
new_state.expiry = expiry_time;
new_state.include_subdomains = include_subdomains;
enabled_hosts_[hashed] = new_state;
}
*dirty = dirtied;
return true;
}
void TransportSecurityState::DeleteSince(const base::Time& time) {
bool dirtied = false;
std::map<std::string, DomainState>::iterator i = enabled_hosts_.begin();
while (i != enabled_hosts_.end()) {
if (i->second.created >= time) {
dirtied = true;
enabled_hosts_.erase(i++);
} else {
i++;
}
}
if (dirtied)
DirtyNotify();
}
void TransportSecurityState::DirtyNotify() {
if (delegate_)
delegate_->StateIsDirty(this);
}
// static
std::string TransportSecurityState::CanonicaliseHost(const std::string& host) {
// We cannot perform the operations as detailed in the spec here as |host|
// has already undergone IDN processing before it reached us. Thus, we check
// that there are no invalid characters in the host and lowercase the result.
std::string new_host;
if (!DNSDomainFromDot(host, &new_host)) {
NOTREACHED();
return std::string();
}
for (size_t i = 0; new_host[i]; i += new_host[i] + 1) {
const unsigned label_length = static_cast<unsigned>(new_host[i]);
if (!label_length)
break;
for (size_t j = 0; j < label_length; ++j) {
// RFC 3490, 4.1, step 3
if (!IsSTD3ASCIIValidCharacter(new_host[i + 1 + j]))
return std::string();
new_host[i + 1 + j] = tolower(new_host[i + 1 + j]);
}
// step 3(b)
if (new_host[i + 1] == '-' ||
new_host[i + label_length] == '-') {
return std::string();
}
}
return new_host;
}
// isPreloadedSTS returns true if the canonicalised hostname should always be
// considered to have STS enabled.
// static
bool TransportSecurityState::isPreloadedSTS(
const std::string& canonicalised_host, bool *include_subdomains) {
// In the medium term this list is likely to just be hardcoded here. This,
// slightly odd, form removes the need for additional relocations records.
static const struct {
uint8 length;
bool include_subdomains;
char dns_name[30];
} preloadedSTS[] = {
{16, false, "\003www\006paypal\003com"},
{16, false, "\003www\006elanex\003biz"},
};
static const size_t numPreloadedSTS =
sizeof(preloadedSTS) / sizeof(preloadedSTS[0]);
for (size_t i = 0; canonicalised_host[i]; i += canonicalised_host[i] + 1) {
for (size_t j = 0; j < numPreloadedSTS; j++) {
if (preloadedSTS[j].length == canonicalised_host.size() + 1 - i &&
(preloadedSTS[j].include_subdomains || i == 0) &&
memcmp(preloadedSTS[j].dns_name, &canonicalised_host[i],
preloadedSTS[j].length) == 0) {
*include_subdomains = preloadedSTS[j].include_subdomains;
return true;
}
}
}
return false;
}
} // namespace
<commit_msg>net: add jottit.com to the STS preloaded list.<commit_after>// Copyright (c) 2009 The Chromium Authors. All rights reserved.
// Use of this source code is governed by a BSD-style license that can be
// found in the LICENSE file.
#include "net/base/transport_security_state.h"
#include "base/base64.h"
#include "base/json/json_reader.h"
#include "base/json/json_writer.h"
#include "base/logging.h"
#include "base/scoped_ptr.h"
#include "base/sha2.h"
#include "base/string_tokenizer.h"
#include "base/string_util.h"
#include "base/values.h"
#include "googleurl/src/gurl.h"
#include "net/base/dns_util.h"
namespace net {
TransportSecurityState::TransportSecurityState()
: delegate_(NULL) {
}
void TransportSecurityState::EnableHost(const std::string& host,
const DomainState& state) {
const std::string canonicalised_host = CanonicaliseHost(host);
if (canonicalised_host.empty())
return;
bool temp;
if (isPreloadedSTS(canonicalised_host, &temp))
return;
char hashed[base::SHA256_LENGTH];
base::SHA256HashString(canonicalised_host, hashed, sizeof(hashed));
// Use the original creation date if we already have this host.
DomainState state_copy(state);
DomainState existing_state;
if (IsEnabledForHost(&existing_state, host))
state_copy.created = existing_state.created;
enabled_hosts_[std::string(hashed, sizeof(hashed))] = state_copy;
DirtyNotify();
}
bool TransportSecurityState::IsEnabledForHost(DomainState* result,
const std::string& host) {
const std::string canonicalised_host = CanonicaliseHost(host);
if (canonicalised_host.empty())
return false;
bool include_subdomains;
if (isPreloadedSTS(canonicalised_host, &include_subdomains)) {
result->created = result->expiry = base::Time::FromTimeT(0);
result->mode = DomainState::MODE_STRICT;
result->include_subdomains = include_subdomains;
return true;
}
base::Time current_time(base::Time::Now());
for (size_t i = 0; canonicalised_host[i]; i += canonicalised_host[i] + 1) {
char hashed_domain[base::SHA256_LENGTH];
base::SHA256HashString(&canonicalised_host[i], &hashed_domain,
sizeof(hashed_domain));
std::map<std::string, DomainState>::iterator j =
enabled_hosts_.find(std::string(hashed_domain, sizeof(hashed_domain)));
if (j == enabled_hosts_.end())
continue;
if (current_time > j->second.expiry) {
enabled_hosts_.erase(j);
DirtyNotify();
continue;
}
*result = j->second;
// If we matched the domain exactly, it doesn't matter what the value of
// include_subdomains is.
if (i == 0)
return true;
return j->second.include_subdomains;
}
return false;
}
// "Strict-Transport-Security" ":"
// "max-age" "=" delta-seconds [ ";" "includeSubDomains" ]
bool TransportSecurityState::ParseHeader(const std::string& value,
int* max_age,
bool* include_subdomains) {
DCHECK(max_age);
DCHECK(include_subdomains);
int max_age_candidate;
enum ParserState {
START,
AFTER_MAX_AGE_LABEL,
AFTER_MAX_AGE_EQUALS,
AFTER_MAX_AGE,
AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER,
AFTER_INCLUDE_SUBDOMAINS,
} state = START;
StringTokenizer tokenizer(value, " \t=;");
tokenizer.set_options(StringTokenizer::RETURN_DELIMS);
while (tokenizer.GetNext()) {
DCHECK(!tokenizer.token_is_delim() || tokenizer.token().length() == 1);
switch (state) {
case START:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (!LowerCaseEqualsASCII(tokenizer.token(), "max-age"))
return false;
state = AFTER_MAX_AGE_LABEL;
break;
case AFTER_MAX_AGE_LABEL:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (*tokenizer.token_begin() != '=')
return false;
DCHECK(tokenizer.token().length() == 1);
state = AFTER_MAX_AGE_EQUALS;
break;
case AFTER_MAX_AGE_EQUALS:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (!StringToInt(tokenizer.token(), &max_age_candidate))
return false;
if (max_age_candidate < 0)
return false;
state = AFTER_MAX_AGE;
break;
case AFTER_MAX_AGE:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (*tokenizer.token_begin() != ';')
return false;
state = AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER;
break;
case AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER:
if (IsAsciiWhitespace(*tokenizer.token_begin()))
continue;
if (!LowerCaseEqualsASCII(tokenizer.token(), "includesubdomains"))
return false;
state = AFTER_INCLUDE_SUBDOMAINS;
break;
case AFTER_INCLUDE_SUBDOMAINS:
if (!IsAsciiWhitespace(*tokenizer.token_begin()))
return false;
break;
default:
NOTREACHED();
}
}
// We've consumed all the input. Let's see what state we ended up in.
switch (state) {
case START:
case AFTER_MAX_AGE_LABEL:
case AFTER_MAX_AGE_EQUALS:
return false;
case AFTER_MAX_AGE:
*max_age = max_age_candidate;
*include_subdomains = false;
return true;
case AFTER_MAX_AGE_INCLUDE_SUB_DOMAINS_DELIMITER:
return false;
case AFTER_INCLUDE_SUBDOMAINS:
*max_age = max_age_candidate;
*include_subdomains = true;
return true;
default:
NOTREACHED();
return false;
}
}
void TransportSecurityState::SetDelegate(
TransportSecurityState::Delegate* delegate) {
delegate_ = delegate;
}
// This function converts the binary hashes, which we store in
// |enabled_hosts_|, to a base64 string which we can include in a JSON file.
static std::wstring HashedDomainToExternalString(const std::string& hashed) {
std::string out;
CHECK(base::Base64Encode(hashed, &out));
return ASCIIToWide(out);
}
// This inverts |HashedDomainToExternalString|, above. It turns an external
// string (from a JSON file) into an internal (binary) string.
static std::string ExternalStringToHashedDomain(const std::wstring& external) {
std::string external_ascii = WideToASCII(external);
std::string out;
if (!base::Base64Decode(external_ascii, &out) ||
out.size() != base::SHA256_LENGTH) {
return std::string();
}
return out;
}
bool TransportSecurityState::Serialise(std::string* output) {
DictionaryValue toplevel;
for (std::map<std::string, DomainState>::const_iterator
i = enabled_hosts_.begin(); i != enabled_hosts_.end(); ++i) {
DictionaryValue* state = new DictionaryValue;
state->SetBoolean(L"include_subdomains", i->second.include_subdomains);
state->SetReal(L"created", i->second.created.ToDoubleT());
state->SetReal(L"expiry", i->second.expiry.ToDoubleT());
switch (i->second.mode) {
case DomainState::MODE_STRICT:
state->SetString(L"mode", "strict");
break;
case DomainState::MODE_OPPORTUNISTIC:
state->SetString(L"mode", "opportunistic");
break;
case DomainState::MODE_SPDY_ONLY:
state->SetString(L"mode", "spdy-only");
break;
default:
NOTREACHED() << "DomainState with unknown mode";
delete state;
continue;
}
toplevel.Set(HashedDomainToExternalString(i->first), state);
}
base::JSONWriter::Write(&toplevel, true /* pretty print */, output);
return true;
}
bool TransportSecurityState::Deserialise(const std::string& input,
bool* dirty) {
enabled_hosts_.clear();
scoped_ptr<Value> value(
base::JSONReader::Read(input, false /* do not allow trailing commas */));
if (!value.get() || !value->IsType(Value::TYPE_DICTIONARY))
return false;
DictionaryValue* dict_value = reinterpret_cast<DictionaryValue*>(value.get());
const base::Time current_time(base::Time::Now());
bool dirtied = false;
for (DictionaryValue::key_iterator i = dict_value->begin_keys();
i != dict_value->end_keys(); ++i) {
DictionaryValue* state;
if (!dict_value->GetDictionaryWithoutPathExpansion(*i, &state))
continue;
bool include_subdomains;
std::string mode_string;
double created;
double expiry;
if (!state->GetBoolean(L"include_subdomains", &include_subdomains) ||
!state->GetString(L"mode", &mode_string) ||
!state->GetReal(L"expiry", &expiry)) {
continue;
}
DomainState::Mode mode;
if (mode_string == "strict") {
mode = DomainState::MODE_STRICT;
} else if (mode_string == "opportunistic") {
mode = DomainState::MODE_OPPORTUNISTIC;
} else if (mode_string == "spdy-only") {
mode = DomainState::MODE_SPDY_ONLY;
} else {
LOG(WARNING) << "Unknown TransportSecurityState mode string found: "
<< mode_string;
continue;
}
base::Time expiry_time = base::Time::FromDoubleT(expiry);
base::Time created_time;
if (state->GetReal(L"created", &created)) {
created_time = base::Time::FromDoubleT(created);
} else {
// We're migrating an old entry with no creation date. Make sure we
// write the new date back in a reasonable time frame.
dirtied = true;
created_time = base::Time::Now();
}
if (expiry_time <= current_time) {
// Make sure we dirty the state if we drop an entry.
dirtied = true;
continue;
}
std::string hashed = ExternalStringToHashedDomain(*i);
if (hashed.empty())
continue;
DomainState new_state;
new_state.mode = mode;
new_state.created = created_time;
new_state.expiry = expiry_time;
new_state.include_subdomains = include_subdomains;
enabled_hosts_[hashed] = new_state;
}
*dirty = dirtied;
return true;
}
void TransportSecurityState::DeleteSince(const base::Time& time) {
bool dirtied = false;
std::map<std::string, DomainState>::iterator i = enabled_hosts_.begin();
while (i != enabled_hosts_.end()) {
if (i->second.created >= time) {
dirtied = true;
enabled_hosts_.erase(i++);
} else {
i++;
}
}
if (dirtied)
DirtyNotify();
}
void TransportSecurityState::DirtyNotify() {
if (delegate_)
delegate_->StateIsDirty(this);
}
// static
std::string TransportSecurityState::CanonicaliseHost(const std::string& host) {
// We cannot perform the operations as detailed in the spec here as |host|
// has already undergone IDN processing before it reached us. Thus, we check
// that there are no invalid characters in the host and lowercase the result.
std::string new_host;
if (!DNSDomainFromDot(host, &new_host)) {
NOTREACHED();
return std::string();
}
for (size_t i = 0; new_host[i]; i += new_host[i] + 1) {
const unsigned label_length = static_cast<unsigned>(new_host[i]);
if (!label_length)
break;
for (size_t j = 0; j < label_length; ++j) {
// RFC 3490, 4.1, step 3
if (!IsSTD3ASCIIValidCharacter(new_host[i + 1 + j]))
return std::string();
new_host[i + 1 + j] = tolower(new_host[i + 1 + j]);
}
// step 3(b)
if (new_host[i + 1] == '-' ||
new_host[i + label_length] == '-') {
return std::string();
}
}
return new_host;
}
// isPreloadedSTS returns true if the canonicalised hostname should always be
// considered to have STS enabled.
// static
bool TransportSecurityState::isPreloadedSTS(
const std::string& canonicalised_host, bool *include_subdomains) {
// In the medium term this list is likely to just be hardcoded here. This,
// slightly odd, form removes the need for additional relocations records.
static const struct {
uint8 length;
bool include_subdomains;
char dns_name[30];
} kPreloadedSTS[] = {
{16, false, "\003www\006paypal\003com"},
{16, false, "\003www\006elanex\003biz"},
{12, true, "\006jottit\003com"},
};
static const size_t kNumPreloadedSTS = ARRAYSIZE_UNSAFE(kPreloadedSTS);
for (size_t i = 0; canonicalised_host[i]; i += canonicalised_host[i] + 1) {
for (size_t j = 0; j < kNumPreloadedSTS; j++) {
if (kPreloadedSTS[j].length == canonicalised_host.size() + 1 - i &&
(kPreloadedSTS[j].include_subdomains || i == 0) &&
memcmp(kPreloadedSTS[j].dns_name, &canonicalised_host[i],
kPreloadedSTS[j].length) == 0) {
*include_subdomains = kPreloadedSTS[j].include_subdomains;
return true;
}
}
}
return false;
}
} // namespace
<|endoftext|> |
<commit_before>#include "FFmpegDecoderVideo.hpp"
#include <osg/Notify>
#include <osg/Timer>
#include <stdexcept>
#include <string.h>
namespace osgFFmpeg {
FFmpegDecoderVideo::FFmpegDecoderVideo(PacketQueue & packets, FFmpegClocks & clocks) :
m_packets(packets),
m_clocks(clocks),
m_stream(0),
m_context(0),
m_codec(0),
m_packet_data(0),
m_bytes_remaining(0),
m_packet_pts(AV_NOPTS_VALUE),
m_writeBuffer(0),
m_user_data(0),
m_publish_func(0),
m_paused(true),
m_exit(false)
#ifdef USE_SWSCALE
,m_swscale_ctx(0)
#endif
{
}
FFmpegDecoderVideo::~FFmpegDecoderVideo()
{
OSG_INFO<<"Destructing FFmpegDecoderVideo..."<<std::endl;
this->close(true);
#ifdef USE_SWSCALE
if (m_swscale_ctx)
{
sws_freeContext(m_swscale_ctx);
m_swscale_ctx = 0;
}
#endif
if (m_context)
{
avcodec_close(m_context);
}
OSG_INFO<<"Destructed FFmpegDecoderVideo"<<std::endl;
}
void FFmpegDecoderVideo::open(AVStream * const stream)
{
m_stream = stream;
m_context = stream->codec;
// Trust the video size given at this point
// (avcodec_open seems to sometimes return a 0x0 size)
m_width = m_context->width;
m_height = m_context->height;
findAspectRatio();
// Find out whether we support Alpha channel
m_alpha_channel = (m_context->pix_fmt == PIX_FMT_YUVA420P);
// Find out the framerate
m_frame_rate = av_q2d(stream->r_frame_rate);
// Find the decoder for the video stream
m_codec = avcodec_find_decoder(m_context->codec_id);
if (m_codec == 0)
throw std::runtime_error("avcodec_find_decoder() failed");
// Inform the codec that we can handle truncated bitstreams
//if (p_codec->capabilities & CODEC_CAP_TRUNCATED)
// m_context->flags |= CODEC_FLAG_TRUNCATED;
// Open codec
if (avcodec_open2(m_context, m_codec, NULL) < 0)
throw std::runtime_error("avcodec_open() failed");
// Allocate video frame
m_frame.reset(avcodec_alloc_frame());
// Allocate converted RGB frame
m_frame_rgba.reset(avcodec_alloc_frame());
m_buffer_rgba[0].resize(avpicture_get_size(PIX_FMT_RGB24, width(), height()));
m_buffer_rgba[1].resize(m_buffer_rgba[0].size());
// Assign appropriate parts of the buffer to image planes in m_frame_rgba
avpicture_fill((AVPicture *) (m_frame_rgba).get(), &(m_buffer_rgba[0])[0], PIX_FMT_RGB24, width(), height());
// Override get_buffer()/release_buffer() from codec context in order to retrieve the PTS of each frame.
m_context->opaque = this;
m_context->get_buffer = getBuffer;
m_context->release_buffer = releaseBuffer;
}
void FFmpegDecoderVideo::close(bool waitForThreadToExit)
{
if (isRunning())
{
m_exit = true;
if (waitForThreadToExit)
join();
}
}
void FFmpegDecoderVideo::pause(bool pause)
{
if(pause)
m_paused = true;
else
m_paused = false;
}
void FFmpegDecoderVideo::run()
{
try
{
decodeLoop();
}
catch (const std::exception & error)
{
OSG_WARN << "FFmpegDecoderVideo::run : " << error.what() << std::endl;
}
catch (...)
{
OSG_WARN << "FFmpegDecoderVideo::run : unhandled exception" << std::endl;
}
}
void FFmpegDecoderVideo::decodeLoop()
{
FFmpegPacket packet;
double pts;
while (! m_exit)
{
// Work on the current packet until we have decoded all of it
while (m_bytes_remaining > 0)
{
// Save global PTS to be stored in m_frame via getBuffer()
m_packet_pts = packet.packet.pts;
// Decode video frame
int frame_finished = 0;
// We want to use the entire packet since some codecs will require extra information for decoding
const int bytes_decoded = avcodec_decode_video2(m_context, m_frame.get(), &frame_finished, &(packet.packet));
if (bytes_decoded < 0)
throw std::runtime_error("avcodec_decode_video failed()");
m_bytes_remaining -= bytes_decoded;
m_packet_data += bytes_decoded;
// Publish the frame if we have decoded a complete frame
if (frame_finished)
{
AVRational timebase;
// Find out the frame pts
if (m_frame->pts != int64_t(AV_NOPTS_VALUE))
{
pts = m_frame->pts;
timebase = m_context->time_base;
}
else if (packet.packet.dts == int64_t(AV_NOPTS_VALUE) &&
m_frame->opaque != 0 &&
*reinterpret_cast<const int64_t*>(m_frame->opaque) != int64_t(AV_NOPTS_VALUE))
{
pts = *reinterpret_cast<const int64_t*>(m_frame->opaque);
timebase = m_stream->time_base;
}
else if (packet.packet.dts != int64_t(AV_NOPTS_VALUE))
{
pts = packet.packet.dts;
timebase = m_stream->time_base;
}
else
{
pts = 0;
timebase = m_context->time_base;
}
pts *= av_q2d(timebase);
const double synched_pts = m_clocks.videoSynchClock(m_frame.get(), av_q2d(timebase), pts);
const double frame_delay = m_clocks.videoRefreshSchedule(synched_pts);
publishFrame(frame_delay, m_clocks.audioDisabled());
}
}
while(m_paused && !m_exit)
{
microSleep(10000);
}
// Get the next packet
pts = 0;
if (packet.valid())
packet.clear();
bool is_empty = true;
packet = m_packets.timedPop(is_empty, 10);
if (! is_empty)
{
if (packet.type == FFmpegPacket::PACKET_DATA)
{
m_bytes_remaining = packet.packet.size;
m_packet_data = packet.packet.data;
}
else if (packet.type == FFmpegPacket::PACKET_FLUSH)
{
avcodec_flush_buffers(m_context);
}
}
}
}
void FFmpegDecoderVideo::findAspectRatio()
{
float ratio = 0.0f;
if (m_context->sample_aspect_ratio.num != 0)
ratio = float(av_q2d(m_context->sample_aspect_ratio));
if (ratio <= 0.0f)
ratio = 1.0f;
m_pixel_aspect_ratio = ratio;
}
int FFmpegDecoderVideo::convert(AVPicture *dst, int dst_pix_fmt, AVPicture *src,
int src_pix_fmt, int src_width, int src_height)
{
osg::Timer_t startTick = osg::Timer::instance()->tick();
#ifdef USE_SWSCALE
if (m_swscale_ctx==0)
{
m_swscale_ctx = sws_getContext(src_width, src_height, (PixelFormat) src_pix_fmt,
src_width, src_height, (PixelFormat) dst_pix_fmt,
/*SWS_BILINEAR*/ SWS_BICUBIC, NULL, NULL, NULL);
}
OSG_DEBUG<<"Using sws_scale ";
int result = sws_scale(m_swscale_ctx,
(src->data), (src->linesize), 0, src_height,
(dst->data), (dst->linesize));
#else
OSG_DEBUG<<"Using img_convert ";
int result = img_convert(dst, dst_pix_fmt, src,
src_pix_fmt, src_width, src_height);
#endif
osg::Timer_t endTick = osg::Timer::instance()->tick();
OSG_DEBUG<<" time = "<<osg::Timer::instance()->delta_m(startTick,endTick)<<"ms"<<std::endl;
return result;
}
void FFmpegDecoderVideo::publishFrame(const double delay, bool audio_disabled)
{
// If no publishing function, just ignore the frame
if (m_publish_func == 0)
return;
#if 1
// new code from Jean-Sebasiten Guay - needs testing as we're unclear on the best solution
// If the display delay is too small, we better skip the frame.
if (!audio_disabled && delay < -0.010)
return;
#else
// original solution that hung on video stream over web.
// If the display delay is too small, we better skip the frame.
if (delay < -0.010)
return;
#endif
AVPicture * const src = (AVPicture *) m_frame.get();
AVPicture * const dst = (AVPicture *) m_frame_rgba.get();
// Assign appropriate parts of the buffer to image planes in m_frame_rgba
avpicture_fill((AVPicture *) (m_frame_rgba).get(), &(m_buffer_rgba[m_writeBuffer])[0], PIX_FMT_RGB24, width(), height());
// Convert YUVA420p (i.e. YUV420p plus alpha channel) using our own routine
if (m_context->pix_fmt == PIX_FMT_YUVA420P)
yuva420pToRgba(dst, src, width(), height());
else
convert(dst, PIX_FMT_RGB24, src, m_context->pix_fmt, width(), height());
// Wait 'delay' seconds before publishing the picture.
int i_delay = static_cast<int>(delay * 1000000 + 0.5);
while (i_delay > 1000)
{
// Avoid infinite/very long loops
if (m_exit)
return;
const int micro_delay = (std::min)(1000000, i_delay);
OpenThreads::Thread::microSleep(micro_delay);
i_delay -= micro_delay;
}
m_writeBuffer = 1-m_writeBuffer;
m_publish_func(* this, m_user_data);
}
void FFmpegDecoderVideo::yuva420pToRgba(AVPicture * const dst, AVPicture * const src, int width, int height)
{
convert(dst, PIX_FMT_RGB24, src, m_context->pix_fmt, width, height);
const size_t bpp = 4;
uint8_t * a_dst = dst->data[0] + 3;
for (int h = 0; h < height; ++h) {
const uint8_t * a_src = src->data[3] + h * src->linesize[3];
for (int w = 0; w < width; ++w) {
*a_dst = *a_src;
a_dst += bpp;
a_src += 1;
}
}
}
int FFmpegDecoderVideo::getBuffer(AVCodecContext * const context, AVFrame * const picture)
{
const FFmpegDecoderVideo * const this_ = reinterpret_cast<const FFmpegDecoderVideo*>(context->opaque);
const int result = avcodec_default_get_buffer(context, picture);
int64_t * p_pts = reinterpret_cast<int64_t*>( av_malloc(sizeof(int64_t)) );
*p_pts = this_->m_packet_pts;
picture->opaque = p_pts;
return result;
}
void FFmpegDecoderVideo::releaseBuffer(AVCodecContext * const context, AVFrame * const picture)
{
if (picture != 0)
av_freep(&picture->opaque);
avcodec_default_release_buffer(context, picture);
}
} // namespace osgFFmpeg
<commit_msg>Added TODO note about RGB -> RGBA<commit_after>#include "FFmpegDecoderVideo.hpp"
#include <osg/Notify>
#include <osg/Timer>
#include <stdexcept>
#include <string.h>
namespace osgFFmpeg {
// TODO - add support for using RGB or RGBA pixel format.
// Note from Jason Daly in a osg-submissions thread, "The pix_fmt field of AVCodecContext will indicate the pixel format of the decoded video"
FFmpegDecoderVideo::FFmpegDecoderVideo(PacketQueue & packets, FFmpegClocks & clocks) :
m_packets(packets),
m_clocks(clocks),
m_stream(0),
m_context(0),
m_codec(0),
m_packet_data(0),
m_bytes_remaining(0),
m_packet_pts(AV_NOPTS_VALUE),
m_writeBuffer(0),
m_user_data(0),
m_publish_func(0),
m_paused(true),
m_exit(false)
#ifdef USE_SWSCALE
,m_swscale_ctx(0)
#endif
{
}
FFmpegDecoderVideo::~FFmpegDecoderVideo()
{
OSG_INFO<<"Destructing FFmpegDecoderVideo..."<<std::endl;
this->close(true);
#ifdef USE_SWSCALE
if (m_swscale_ctx)
{
sws_freeContext(m_swscale_ctx);
m_swscale_ctx = 0;
}
#endif
if (m_context)
{
avcodec_close(m_context);
}
OSG_INFO<<"Destructed FFmpegDecoderVideo"<<std::endl;
}
void FFmpegDecoderVideo::open(AVStream * const stream)
{
m_stream = stream;
m_context = stream->codec;
// Trust the video size given at this point
// (avcodec_open seems to sometimes return a 0x0 size)
m_width = m_context->width;
m_height = m_context->height;
findAspectRatio();
// Find out whether we support Alpha channel
m_alpha_channel = (m_context->pix_fmt == PIX_FMT_YUVA420P);
// Find out the framerate
m_frame_rate = av_q2d(stream->r_frame_rate);
// Find the decoder for the video stream
m_codec = avcodec_find_decoder(m_context->codec_id);
if (m_codec == 0)
throw std::runtime_error("avcodec_find_decoder() failed");
// Inform the codec that we can handle truncated bitstreams
//if (p_codec->capabilities & CODEC_CAP_TRUNCATED)
// m_context->flags |= CODEC_FLAG_TRUNCATED;
// Open codec
if (avcodec_open2(m_context, m_codec, NULL) < 0)
throw std::runtime_error("avcodec_open() failed");
// Allocate video frame
m_frame.reset(avcodec_alloc_frame());
// Allocate converted RGB frame
m_frame_rgba.reset(avcodec_alloc_frame());
m_buffer_rgba[0].resize(avpicture_get_size(PIX_FMT_RGB24, width(), height()));
m_buffer_rgba[1].resize(m_buffer_rgba[0].size());
// Assign appropriate parts of the buffer to image planes in m_frame_rgba
avpicture_fill((AVPicture *) (m_frame_rgba).get(), &(m_buffer_rgba[0])[0], PIX_FMT_RGB24, width(), height());
// Override get_buffer()/release_buffer() from codec context in order to retrieve the PTS of each frame.
m_context->opaque = this;
m_context->get_buffer = getBuffer;
m_context->release_buffer = releaseBuffer;
}
void FFmpegDecoderVideo::close(bool waitForThreadToExit)
{
if (isRunning())
{
m_exit = true;
if (waitForThreadToExit)
join();
}
}
void FFmpegDecoderVideo::pause(bool pause)
{
if(pause)
m_paused = true;
else
m_paused = false;
}
void FFmpegDecoderVideo::run()
{
try
{
decodeLoop();
}
catch (const std::exception & error)
{
OSG_WARN << "FFmpegDecoderVideo::run : " << error.what() << std::endl;
}
catch (...)
{
OSG_WARN << "FFmpegDecoderVideo::run : unhandled exception" << std::endl;
}
}
void FFmpegDecoderVideo::decodeLoop()
{
FFmpegPacket packet;
double pts;
while (! m_exit)
{
// Work on the current packet until we have decoded all of it
while (m_bytes_remaining > 0)
{
// Save global PTS to be stored in m_frame via getBuffer()
m_packet_pts = packet.packet.pts;
// Decode video frame
int frame_finished = 0;
// We want to use the entire packet since some codecs will require extra information for decoding
const int bytes_decoded = avcodec_decode_video2(m_context, m_frame.get(), &frame_finished, &(packet.packet));
if (bytes_decoded < 0)
throw std::runtime_error("avcodec_decode_video failed()");
m_bytes_remaining -= bytes_decoded;
m_packet_data += bytes_decoded;
// Publish the frame if we have decoded a complete frame
if (frame_finished)
{
AVRational timebase;
// Find out the frame pts
if (m_frame->pts != int64_t(AV_NOPTS_VALUE))
{
pts = m_frame->pts;
timebase = m_context->time_base;
}
else if (packet.packet.dts == int64_t(AV_NOPTS_VALUE) &&
m_frame->opaque != 0 &&
*reinterpret_cast<const int64_t*>(m_frame->opaque) != int64_t(AV_NOPTS_VALUE))
{
pts = *reinterpret_cast<const int64_t*>(m_frame->opaque);
timebase = m_stream->time_base;
}
else if (packet.packet.dts != int64_t(AV_NOPTS_VALUE))
{
pts = packet.packet.dts;
timebase = m_stream->time_base;
}
else
{
pts = 0;
timebase = m_context->time_base;
}
pts *= av_q2d(timebase);
const double synched_pts = m_clocks.videoSynchClock(m_frame.get(), av_q2d(timebase), pts);
const double frame_delay = m_clocks.videoRefreshSchedule(synched_pts);
publishFrame(frame_delay, m_clocks.audioDisabled());
}
}
while(m_paused && !m_exit)
{
microSleep(10000);
}
// Get the next packet
pts = 0;
if (packet.valid())
packet.clear();
bool is_empty = true;
packet = m_packets.timedPop(is_empty, 10);
if (! is_empty)
{
if (packet.type == FFmpegPacket::PACKET_DATA)
{
m_bytes_remaining = packet.packet.size;
m_packet_data = packet.packet.data;
}
else if (packet.type == FFmpegPacket::PACKET_FLUSH)
{
avcodec_flush_buffers(m_context);
}
}
}
}
void FFmpegDecoderVideo::findAspectRatio()
{
float ratio = 0.0f;
if (m_context->sample_aspect_ratio.num != 0)
ratio = float(av_q2d(m_context->sample_aspect_ratio));
if (ratio <= 0.0f)
ratio = 1.0f;
m_pixel_aspect_ratio = ratio;
}
int FFmpegDecoderVideo::convert(AVPicture *dst, int dst_pix_fmt, AVPicture *src,
int src_pix_fmt, int src_width, int src_height)
{
osg::Timer_t startTick = osg::Timer::instance()->tick();
#ifdef USE_SWSCALE
if (m_swscale_ctx==0)
{
m_swscale_ctx = sws_getContext(src_width, src_height, (PixelFormat) src_pix_fmt,
src_width, src_height, (PixelFormat) dst_pix_fmt,
/*SWS_BILINEAR*/ SWS_BICUBIC, NULL, NULL, NULL);
}
OSG_DEBUG<<"Using sws_scale ";
int result = sws_scale(m_swscale_ctx,
(src->data), (src->linesize), 0, src_height,
(dst->data), (dst->linesize));
#else
OSG_DEBUG<<"Using img_convert ";
int result = img_convert(dst, dst_pix_fmt, src,
src_pix_fmt, src_width, src_height);
#endif
osg::Timer_t endTick = osg::Timer::instance()->tick();
OSG_DEBUG<<" time = "<<osg::Timer::instance()->delta_m(startTick,endTick)<<"ms"<<std::endl;
return result;
}
void FFmpegDecoderVideo::publishFrame(const double delay, bool audio_disabled)
{
// If no publishing function, just ignore the frame
if (m_publish_func == 0)
return;
#if 1
// new code from Jean-Sebasiten Guay - needs testing as we're unclear on the best solution
// If the display delay is too small, we better skip the frame.
if (!audio_disabled && delay < -0.010)
return;
#else
// original solution that hung on video stream over web.
// If the display delay is too small, we better skip the frame.
if (delay < -0.010)
return;
#endif
AVPicture * const src = (AVPicture *) m_frame.get();
AVPicture * const dst = (AVPicture *) m_frame_rgba.get();
// Assign appropriate parts of the buffer to image planes in m_frame_rgba
avpicture_fill((AVPicture *) (m_frame_rgba).get(), &(m_buffer_rgba[m_writeBuffer])[0], PIX_FMT_RGB24, width(), height());
// Convert YUVA420p (i.e. YUV420p plus alpha channel) using our own routine
if (m_context->pix_fmt == PIX_FMT_YUVA420P)
yuva420pToRgba(dst, src, width(), height());
else
convert(dst, PIX_FMT_RGB24, src, m_context->pix_fmt, width(), height());
// Wait 'delay' seconds before publishing the picture.
int i_delay = static_cast<int>(delay * 1000000 + 0.5);
while (i_delay > 1000)
{
// Avoid infinite/very long loops
if (m_exit)
return;
const int micro_delay = (std::min)(1000000, i_delay);
OpenThreads::Thread::microSleep(micro_delay);
i_delay -= micro_delay;
}
m_writeBuffer = 1-m_writeBuffer;
m_publish_func(* this, m_user_data);
}
void FFmpegDecoderVideo::yuva420pToRgba(AVPicture * const dst, AVPicture * const src, int width, int height)
{
convert(dst, PIX_FMT_RGB24, src, m_context->pix_fmt, width, height);
const size_t bpp = 4;
uint8_t * a_dst = dst->data[0] + 3;
for (int h = 0; h < height; ++h) {
const uint8_t * a_src = src->data[3] + h * src->linesize[3];
for (int w = 0; w < width; ++w) {
*a_dst = *a_src;
a_dst += bpp;
a_src += 1;
}
}
}
int FFmpegDecoderVideo::getBuffer(AVCodecContext * const context, AVFrame * const picture)
{
const FFmpegDecoderVideo * const this_ = reinterpret_cast<const FFmpegDecoderVideo*>(context->opaque);
const int result = avcodec_default_get_buffer(context, picture);
int64_t * p_pts = reinterpret_cast<int64_t*>( av_malloc(sizeof(int64_t)) );
*p_pts = this_->m_packet_pts;
picture->opaque = p_pts;
return result;
}
void FFmpegDecoderVideo::releaseBuffer(AVCodecContext * const context, AVFrame * const picture)
{
if (picture != 0)
av_freep(&picture->opaque);
avcodec_default_release_buffer(context, picture);
}
} // namespace osgFFmpeg
<|endoftext|> |
<commit_before>//===----------------------------------------------------------------------===//
//
// The LLVM Compiler Infrastructure
//
// This file is dual licensed under the MIT and the University of Illinois Open
// Source Licenses. See LICENSE.TXT for details.
//
//===----------------------------------------------------------------------===//
// <future>
// enum class launch
// {
// async = 1,
// deferred = 2,
// any = async | deferred
// };
#include <future>
int main()
{
static_assert(static_cast<int>(std::launch::any) ==
(static_cast<int>(std::launch::async) | static_cast<int>(std::launch::deferred)), "");
static_assert(static_cast<int>(std::launch::async) == 1, "");
static_assert(static_cast<int>(std::launch::deferred) == 2, "");
}
<commit_msg>Add operators to make launch a bitmask type. Searched all of the standard, and libc++ to see if this error occurred elsewhere and didn't see any other place. This fixes http://llvm.org/bugs/show_bug.cgi?id=16207<commit_after>//===----------------------------------------------------------------------===//
//
// The LLVM Compiler Infrastructure
//
// This file is dual licensed under the MIT and the University of Illinois Open
// Source Licenses. See LICENSE.TXT for details.
//
//===----------------------------------------------------------------------===//
// <future>
// enum class launch
// {
// async = 1,
// deferred = 2,
// any = async | deferred
// };
#include <future>
#include <cassert>
int main()
{
#ifdef _LIBCPP_HAS_NO_STRONG_ENUMS
static_assert(static_cast<int>(std::launch::any) ==
(static_cast<int>(std::launch::async) | static_cast<int>(std::launch::deferred)), "");
#else
static_assert(std::launch::any == (std::launch::async | std::launch::deferred), "");
static_assert(std::launch(0) == (std::launch::async & std::launch::deferred), "");
static_assert(std::launch::any == (std::launch::async ^ std::launch::deferred), "");
static_assert(std::launch(~1) == ~std::launch::async, "");
std::launch x = std::launch::async;
x &= std::launch::deferred;
assert(x == std::launch(0));
x = std::launch::async;
x |= std::launch::deferred;
assert(x == std::launch::any);
x ^= std::launch::deferred;
assert(x == std::launch::async);
#endif
static_assert(static_cast<int>(std::launch::async) == 1, "");
static_assert(static_cast<int>(std::launch::deferred) == 2, "");
}
<|endoftext|> |
<commit_before>/*
* Copyright 2008-2013 NVIDIA Corporation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <thrust/detail/config.h>
#include <thrust/detail/allocator/temporary_allocator.h>
#include <thrust/detail/temporary_buffer.h>
#include <thrust/system/detail/bad_alloc.h>
#include <thrust/system/cuda/detail/terminate.h>
#include <cassert>
namespace thrust
{
namespace detail
{
template<typename T, typename System>
__host__ __device__
typename temporary_allocator<T,System>::pointer
temporary_allocator<T,System>
::allocate(typename temporary_allocator<T,System>::size_type cnt)
{
pointer_and_size result = thrust::get_temporary_buffer<T>(system(), cnt);
// handle failure
if(result.second < cnt)
{
// deallocate and throw
// note that we pass cnt to deallocate, not a value derived from result.second
deallocate(result.first, cnt);
#if !defined(__CUDA_ARCH__)
throw thrust::system::detail::bad_alloc("temporary_buffer::allocate: get_temporary_buffer failed");
#else
thrust::system::cuda::detail::terminate_with_message("temporary_buffer::allocate: get_temporary_buffer failed");
#endif
} // end if
return result.first;
} // end temporary_allocator::allocate()
template<typename T, typename System>
__host__ __device__
void temporary_allocator<T,System>
::deallocate(typename temporary_allocator<T,System>::pointer p, typename temporary_allocator<T,System>::size_type n)
{
return thrust::return_temporary_buffer(system(), p);
} // end temporary_allocator
} // end detail
} // end thrust
<commit_msg>Don't #include a cuda-specific header in temporary_allocator unless the compiler is nvcc Addresses the regression mentioned in #386<commit_after>/*
* Copyright 2008-2013 NVIDIA Corporation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <thrust/detail/config.h>
#include <thrust/detail/allocator/temporary_allocator.h>
#include <thrust/detail/temporary_buffer.h>
#include <thrust/system/detail/bad_alloc.h>
#include <cassert>
#ifdef __NVCC__
#include <thrust/system/cuda/detail/terminate.h>
#endif
namespace thrust
{
namespace detail
{
template<typename T, typename System>
__host__ __device__
typename temporary_allocator<T,System>::pointer
temporary_allocator<T,System>
::allocate(typename temporary_allocator<T,System>::size_type cnt)
{
pointer_and_size result = thrust::get_temporary_buffer<T>(system(), cnt);
// handle failure
if(result.second < cnt)
{
// deallocate and throw
// note that we pass cnt to deallocate, not a value derived from result.second
deallocate(result.first, cnt);
#if !defined(__CUDA_ARCH__)
throw thrust::system::detail::bad_alloc("temporary_buffer::allocate: get_temporary_buffer failed");
#else
thrust::system::cuda::detail::terminate_with_message("temporary_buffer::allocate: get_temporary_buffer failed");
#endif
} // end if
return result.first;
} // end temporary_allocator::allocate()
template<typename T, typename System>
__host__ __device__
void temporary_allocator<T,System>
::deallocate(typename temporary_allocator<T,System>::pointer p, typename temporary_allocator<T,System>::size_type n)
{
return thrust::return_temporary_buffer(system(), p);
} // end temporary_allocator
} // end detail
} // end thrust
<|endoftext|> |
<commit_before>//==============================================================================
// Enhanced tree view widget
//==============================================================================
#include "treeviewwidget.h"
//==============================================================================
#include <QDrag>
#include <QHeaderView>
#include <QMouseEvent>
#include <QStandardItemModel>
//==============================================================================
namespace OpenCOR {
namespace Core {
//==============================================================================
TreeViewWidget::TreeViewWidget(QWidget *pParent) :
QTreeView(pParent),
CommonWidget(pParent)
{
// Set some properties for our tree view widget
setAllColumnsShowFocus(true);
#ifdef Q_OS_MAC
setAttribute(Qt::WA_MacShowFocusRect, 0);
// Note: the above removes the focus border since it messes up the look of
// our tree view widget...
#endif
setFrameShape(QFrame::NoFrame);
setSelectionMode(QAbstractItemView::ExtendedSelection);
setUniformRowHeights(true);
}
//==============================================================================
void TreeViewWidget::resizeColumnsToContents()
{
// Resize all our columns to their contents
for (int i = 0, iMax = header()->count(); i < iMax; ++i)
resizeColumnToContents(i);
}
//==============================================================================
void TreeViewWidget::selectItem(const int &pRow, const int &pColumn)
{
// Select the requested item, if any
QStandardItemModel *treeViewModel = qobject_cast<QStandardItemModel *>(model());
if (treeViewModel) {
// The tree view has a model associated with it, so we can retrieve the
// requested item
QStandardItem *treeViewItem = treeViewModel->invisibleRootItem()->child(pRow, pColumn);
if (treeViewItem)
// The requested item exists, so select it...
setCurrentIndex(treeViewItem->index());
}
}
//==============================================================================
void TreeViewWidget::selectFirstItem()
{
// Select the first item
selectItem();
}
//==============================================================================
bool TreeViewWidget::isEditing() const
{
// Return whether our tree view widget is in editing mode
return state() == QAbstractItemView::EditingState;
}
//==============================================================================
QSize TreeViewWidget::sizeHint() const
{
// Suggest a default size for our tree view widget
// Note: this is critical if we want a docked widget, with a tree view
// widget on it, to have a decent size when docked to the main window
return defaultSize(0.15);
}
//==============================================================================
void TreeViewWidget::keyPressEvent(QKeyEvent *pEvent)
{
// Check some key combinations
if ( !(pEvent->modifiers() & Qt::ShiftModifier)
&& !(pEvent->modifiers() & Qt::ControlModifier)
&& !(pEvent->modifiers() & Qt::AltModifier)
&& !(pEvent->modifiers() & Qt::MetaModifier)) {
// None of the modifiers is selected
if (pEvent->key() == Qt::Key_Left) {
// The user wants to collapse the current item or go to its parent,
// depending on the collapsed state of the current item
QModelIndex currIndex = currentIndex();
if (isExpanded(currIndex)) {
// The current item is expanded, so collapse it
setExpanded(currIndex, false);
// Accept the event
pEvent->accept();
} else {
// The current item is collapsed, so select its parent, but
// only if it has a parent
if (currIndex.parent() != QModelIndex()) {
setCurrentIndex(currIndex.parent());
// Accept the event
pEvent->accept();
} else {
// Default handling of the event
QTreeView::keyPressEvent(pEvent);
}
}
} else if (pEvent->key() == Qt::Key_Right) {
// The user wants to expand the current item or go to its first
// child, should it have children
QModelIndex currIndex = currentIndex();
if (model()->hasChildren(currIndex)) {
if (!isExpanded(currIndex)) {
// The current item is collapsed, so expand it
setExpanded(currIndex, true);
// Accept the event
pEvent->accept();
} else {
// The current item is expanded, so select its first child
setCurrentIndex(currIndex.child(0, 0));
// Accept the event
pEvent->accept();
}
} else {
// The current item doesn't have any children, so do nothing
// Note: normally, we would do the default handling of the
// event, but this will potentially shift the whole tree
// view contents to the right, so do nothing indeed...
;
}
} else {
// Default handling of the event
QTreeView::keyPressEvent(pEvent);
}
} else {
// Default handling of the event
QTreeView::keyPressEvent(pEvent);
}
}
//==============================================================================
void TreeViewWidget::mouseDoubleClickEvent(QMouseEvent *pEvent)
{
// Retrieve the index of the item which row is the same as our current item,
// but which column is 0, so that we can expand/collapse properly
QModelIndex currIndex = currentIndex();
if (model()->hasChildren(currIndex)) {
// The item has some children, so expand/collapse it
setExpanded(currIndex, !isExpanded(currIndex));
// Accept the event
pEvent->accept();
} else {
// Default handling of the event
QTreeView::mouseDoubleClickEvent(pEvent);
}
}
//==============================================================================
void TreeViewWidget::startDrag(Qt::DropActions pSupportedActions)
{
// This a reimplementation of QAbstractItemView::startDrag, so that we can
// provide OpenCOR with a better pixmap for the drag object
// Note: indeed, on Windows, the pixmap only shows the dragged item that are
// visible in the QTreeView. Also, if there an item covers several
// columns, then the pixmap will show several 'cells' some of them
// empty if a column is empty, so... instead we want to provide a
// generic pixmap which looks 'good' on all platforms...
// Retrieve the selected draggable items, if any
// Note: the following code is based on
// QAbstractItemViewPrivate::selectedDraggableIndexes...
QModelIndexList selectedDraggableIndexes = selectedIndexes();
for (int i = selectedDraggableIndexes.count()-1; i >= 0; --i)
if ( !(model()->flags(selectedDraggableIndexes[i]) & Qt::ItemIsDragEnabled)
|| selectedDraggableIndexes[i].column())
// The current selected item is not draggable or is not in the first
// column
// Note: regarding the test on the column number, it is because we
// may have a model data that requires several columns (e.g.
// QFileSystemModel) in which case selectedIndexes would
// return a number of indexes equal to the number of rows
// times the number of columns while we only want a number of
// indexes to be equal to the number of rows (since we have a
// selection mode of QAbstractItemView::ExtendedSelection)
selectedDraggableIndexes.removeAt(i);
// Start the dragging action is there is at least one selected draggable
// item
if (selectedDraggableIndexes.count()) {
// There is at least one selected draggable item, so create a QMimeData
// object for it
QMimeData *mimeData = model()->mimeData(selectedDraggableIndexes);
if (!mimeData)
return;
// Create the pixmap that will be associated with the dragging action
QPixmap pixmap((selectedDraggableIndexes.count() == 1)?
":oxygen/mimetypes/application-x-zerosize.png":
":oxygen/places/document-multiple.png");
// Create the drag object
QDrag *drag = new QDrag(this);
drag->setMimeData(mimeData);
drag->setPixmap(pixmap);
drag->setHotSpot(QPoint(0.5*pixmap.width(), 0.5*pixmap.height()));
// Do the dragging itself
Qt::DropAction realDefaultDropAction = Qt::IgnoreAction;
if ( (defaultDropAction() != Qt::IgnoreAction)
&& (pSupportedActions & defaultDropAction()))
realDefaultDropAction = defaultDropAction();
else if ( (pSupportedActions & Qt::CopyAction)
&& (dragDropMode() != QAbstractItemView::InternalMove))
realDefaultDropAction = Qt::CopyAction;
if (drag->exec(pSupportedActions, realDefaultDropAction) == Qt::MoveAction) {
// We want to move the items
// Note: the following code is based on
// QAbstractItemViewPrivate::clearOrRemove...
const QItemSelection selection = selectionModel()->selection();
if (!dragDropOverwriteMode()) {
foreach (const QItemSelectionRange &itemSelectionRange, selection) {
QModelIndex parent = itemSelectionRange.parent();
if (itemSelectionRange.left())
continue;
if (itemSelectionRange.right() != (model()->columnCount(parent)-1))
continue;
model()->removeRows(itemSelectionRange.top(),
itemSelectionRange.bottom()-itemSelectionRange.top()+1,
parent);
}
} else {
// We can't remove the rows so reset the items (i.e. the view
// is like a table)
foreach (const QModelIndex &index, selection.indexes()) {
QMap<int, QVariant> roles = model()->itemData(index);
for (QMap<int, QVariant>::Iterator iter = roles.begin(),
iterEnd = roles.end();
iter != iterEnd; ++iter)
iter.value() = QVariant();
model()->setItemData(index, roles);
}
}
}
}
}
//==============================================================================
} // namespace Core
} // namespace OpenCOR
//==============================================================================
// End of file
//==============================================================================
<commit_msg>Reverted what I thought was some 'safe' cleaning up.<commit_after>//==============================================================================
// Enhanced tree view widget
//==============================================================================
#include "treeviewwidget.h"
//==============================================================================
#include <QDrag>
#include <QHeaderView>
#include <QMouseEvent>
#include <QStandardItemModel>
//==============================================================================
namespace OpenCOR {
namespace Core {
//==============================================================================
TreeViewWidget::TreeViewWidget(QWidget *pParent) :
QTreeView(pParent),
CommonWidget(pParent)
{
// Set some properties for our tree view widget
setAllColumnsShowFocus(true);
#ifdef Q_OS_MAC
setAttribute(Qt::WA_MacShowFocusRect, 0);
// Note: the above removes the focus border since it messes up the look of
// our tree view widget...
#endif
setFrameShape(QFrame::NoFrame);
setSelectionMode(QAbstractItemView::ExtendedSelection);
setUniformRowHeights(true);
}
//==============================================================================
void TreeViewWidget::resizeColumnsToContents()
{
// Resize all our columns to their contents
for (int i = 0, iMax = header()->count(); i < iMax; ++i)
resizeColumnToContents(i);
}
//==============================================================================
void TreeViewWidget::selectItem(const int &pRow, const int &pColumn)
{
// Select the requested item, if any
QStandardItemModel *treeViewModel = qobject_cast<QStandardItemModel *>(model());
if (treeViewModel) {
// The tree view has a model associated with it, so we can retrieve the
// requested item
QStandardItem *treeViewItem = treeViewModel->invisibleRootItem()->child(pRow, pColumn);
if (treeViewItem)
// The requested item exists, so select it...
setCurrentIndex(treeViewItem->index());
}
}
//==============================================================================
void TreeViewWidget::selectFirstItem()
{
// Select the first item
selectItem();
}
//==============================================================================
bool TreeViewWidget::isEditing() const
{
// Return whether our tree view widget is in editing mode
return state() == QAbstractItemView::EditingState;
}
//==============================================================================
QSize TreeViewWidget::sizeHint() const
{
// Suggest a default size for our tree view widget
// Note: this is critical if we want a docked widget, with a tree view
// widget on it, to have a decent size when docked to the main window
return defaultSize(0.15);
}
//==============================================================================
void TreeViewWidget::keyPressEvent(QKeyEvent *pEvent)
{
// Check some key combinations
if ( !(pEvent->modifiers() & Qt::ShiftModifier)
&& !(pEvent->modifiers() & Qt::ControlModifier)
&& !(pEvent->modifiers() & Qt::AltModifier)
&& !(pEvent->modifiers() & Qt::MetaModifier)) {
// None of the modifiers is selected
if (pEvent->key() == Qt::Key_Left) {
// The user wants to collapse the current item or go to its parent,
// depending on the collapsed state of the current item
QModelIndex currIndex = currentIndex();
if (isExpanded(currIndex)) {
// The current item is expanded, so collapse it
setExpanded(currIndex, false);
// Accept the event
pEvent->accept();
} else {
// The current item is collapsed, so select its parent, but
// only if it has a parent
if (currIndex.parent() != QModelIndex()) {
setCurrentIndex(currIndex.parent());
// Accept the event
pEvent->accept();
} else {
// Default handling of the event
QTreeView::keyPressEvent(pEvent);
}
}
} else if (pEvent->key() == Qt::Key_Right) {
// The user wants to expand the current item or go to its first
// child, should it have children
QModelIndex currIndex = currentIndex();
if (model()->hasChildren(currIndex)) {
if (!isExpanded(currIndex)) {
// The current item is collapsed, so expand it
setExpanded(currIndex, true);
// Accept the event
pEvent->accept();
} else {
// The current item is expanded, so select its first child
setCurrentIndex(currIndex.child(0, 0));
// Accept the event
pEvent->accept();
}
} else {
// The current item doesn't have any children, so do nothing
// Note: normally, we would do the default handling of the
// event, but this will potentially shift the whole tree
// view contents to the right, so do nothing indeed...
;
}
} else {
// Default handling of the event
QTreeView::keyPressEvent(pEvent);
}
} else {
// Default handling of the event
QTreeView::keyPressEvent(pEvent);
}
}
//==============================================================================
void TreeViewWidget::mouseDoubleClickEvent(QMouseEvent *pEvent)
{
// Retrieve the index of the item which row is the same as our current item,
// but which column is 0, so that we can expand/collapse properly
// Note: to retrieve the current index, we would normally use
// currentIndex(), but we may not be double clicking on an item, so...
QModelIndex currIndex = indexAt(pEvent->pos());
QModelIndex index = model()->index(currIndex.row(), 0, currIndex.parent());
if (model()->hasChildren(index)) {
// The item has some children, so expand/collapse it
setExpanded(index, !isExpanded(index));
// Accept the event
pEvent->accept();
} else {
// Default handling of the event
QTreeView::mouseDoubleClickEvent(pEvent);
}
}
//==============================================================================
void TreeViewWidget::startDrag(Qt::DropActions pSupportedActions)
{
// This a reimplementation of QAbstractItemView::startDrag, so that we can
// provide OpenCOR with a better pixmap for the drag object
// Note: indeed, on Windows, the pixmap only shows the dragged item that are
// visible in the QTreeView. Also, if there an item covers several
// columns, then the pixmap will show several 'cells' some of them
// empty if a column is empty, so... instead we want to provide a
// generic pixmap which looks 'good' on all platforms...
// Retrieve the selected draggable items, if any
// Note: the following code is based on
// QAbstractItemViewPrivate::selectedDraggableIndexes...
QModelIndexList selectedDraggableIndexes = selectedIndexes();
for (int i = selectedDraggableIndexes.count()-1; i >= 0; --i)
if ( !(model()->flags(selectedDraggableIndexes[i]) & Qt::ItemIsDragEnabled)
|| selectedDraggableIndexes[i].column())
// The current selected item is not draggable or is not in the first
// column
// Note: regarding the test on the column number, it is because we
// may have a model data that requires several columns (e.g.
// QFileSystemModel) in which case selectedIndexes would
// return a number of indexes equal to the number of rows
// times the number of columns while we only want a number of
// indexes to be equal to the number of rows (since we have a
// selection mode of QAbstractItemView::ExtendedSelection)
selectedDraggableIndexes.removeAt(i);
// Start the dragging action is there is at least one selected draggable
// item
if (selectedDraggableIndexes.count()) {
// There is at least one selected draggable item, so create a QMimeData
// object for it
QMimeData *mimeData = model()->mimeData(selectedDraggableIndexes);
if (!mimeData)
return;
// Create the pixmap that will be associated with the dragging action
QPixmap pixmap((selectedDraggableIndexes.count() == 1)?
":oxygen/mimetypes/application-x-zerosize.png":
":oxygen/places/document-multiple.png");
// Create the drag object
QDrag *drag = new QDrag(this);
drag->setMimeData(mimeData);
drag->setPixmap(pixmap);
drag->setHotSpot(QPoint(0.5*pixmap.width(), 0.5*pixmap.height()));
// Do the dragging itself
Qt::DropAction realDefaultDropAction = Qt::IgnoreAction;
if ( (defaultDropAction() != Qt::IgnoreAction)
&& (pSupportedActions & defaultDropAction()))
realDefaultDropAction = defaultDropAction();
else if ( (pSupportedActions & Qt::CopyAction)
&& (dragDropMode() != QAbstractItemView::InternalMove))
realDefaultDropAction = Qt::CopyAction;
if (drag->exec(pSupportedActions, realDefaultDropAction) == Qt::MoveAction) {
// We want to move the items
// Note: the following code is based on
// QAbstractItemViewPrivate::clearOrRemove...
const QItemSelection selection = selectionModel()->selection();
if (!dragDropOverwriteMode()) {
foreach (const QItemSelectionRange &itemSelectionRange, selection) {
QModelIndex parent = itemSelectionRange.parent();
if (itemSelectionRange.left())
continue;
if (itemSelectionRange.right() != (model()->columnCount(parent)-1))
continue;
model()->removeRows(itemSelectionRange.top(),
itemSelectionRange.bottom()-itemSelectionRange.top()+1,
parent);
}
} else {
// We can't remove the rows so reset the items (i.e. the view
// is like a table)
foreach (const QModelIndex &index, selection.indexes()) {
QMap<int, QVariant> roles = model()->itemData(index);
for (QMap<int, QVariant>::Iterator iter = roles.begin(),
iterEnd = roles.end();
iter != iterEnd; ++iter)
iter.value() = QVariant();
model()->setItemData(index, roles);
}
}
}
}
}
//==============================================================================
} // namespace Core
} // namespace OpenCOR
//==============================================================================
// End of file
//==============================================================================
<|endoftext|> |
<commit_before>/*
* Copyright 2008-2009 NVIDIA Corporation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <thrust/functional.h>
#include <thrust/transform.h>
#include <thrust/replace.h>
#include <thrust/iterator/zip_iterator.h>
#include <thrust/iterator/iterator_traits.h>
#include <thrust/detail/device/scan.h>
#include <thrust/detail/raw_buffer.h>
namespace thrust
{
namespace detail
{
namespace device
{
namespace generic
{
namespace detail
{
template <typename OutputType, typename HeadFlagType, typename AssociativeOperator>
struct segmented_scan_functor
{
AssociativeOperator binary_op;
typedef typename thrust::tuple<OutputType, HeadFlagType> result_type;
__host__ __device__
segmented_scan_functor(AssociativeOperator _binary_op) : binary_op(_binary_op) {}
__host__ __device__
result_type operator()(result_type a, result_type b)
{
return result_type(thrust::get<1>(b) ? thrust::get<0>(b) : binary_op(thrust::get<0>(a), thrust::get<0>(b)),
thrust::get<1>(a) | thrust::get<1>(b));
}
};
} // end namespace detail
template<typename InputIterator1,
typename InputIterator2,
typename OutputIterator,
typename AssociativeOperator,
typename BinaryPredicate>
OutputIterator inclusive_segmented_scan(InputIterator1 first1,
InputIterator1 last1,
InputIterator2 first2,
OutputIterator result,
AssociativeOperator binary_op,
BinaryPredicate pred)
{
typedef typename thrust::iterator_traits<OutputIterator>::value_type OutputType;
typedef typename thrust::iterator_space<OutputIterator>::type Space;
typedef unsigned int HeadFlagType;
if(first1 != last1)
{
const size_t n = last1 - first1;
// compute head flags
thrust::detail::raw_buffer<HeadFlagType,Space> flags(n);
flags[0] = 1; thrust::transform(first2, first2 + (n - 1), first2 + 1, flags.begin() + 1, thrust::not2(pred));
// scan key-flag tuples,
// For additional details refer to Section 2 of the following paper
// S. Sengupta, M. Harris, and M. Garland. "Efficient parallel scan algorithms for GPUs"
// NVIDIA Technical Report NVR-2008-003, December 2008
// http://mgarland.org/files/papers/nvr-2008-003.pdf
thrust::detail::device::inclusive_scan
(thrust::make_zip_iterator(thrust::make_tuple(first1, flags.begin())),
thrust::make_zip_iterator(thrust::make_tuple(last1, flags.end())),
thrust::make_zip_iterator(thrust::make_tuple(result, flags.begin())),
detail::segmented_scan_functor<OutputType, HeadFlagType, AssociativeOperator>(binary_op));
}
return result + (last1 - first1);
}
template<typename InputIterator1,
typename InputIterator2,
typename OutputIterator,
typename T,
typename AssociativeOperator,
typename BinaryPredicate>
OutputIterator exclusive_segmented_scan(InputIterator1 first1,
InputIterator1 last1,
InputIterator2 first2,
OutputIterator result,
const T init,
AssociativeOperator binary_op,
BinaryPredicate pred)
{
typedef typename thrust::iterator_traits<OutputIterator>::value_type OutputType;
typedef typename thrust::iterator_space<OutputIterator>::type Space;
typedef unsigned int HeadFlagType;
if(first1 != last1)
{
const size_t n = last1 - first1;
InputIterator2 last2 = first2 + n;
// compute head flags
thrust::detail::raw_buffer<HeadFlagType,Space> flags(n);
flags[0] = 1; thrust::transform(first2, last2 - 1, first2 + 1, flags.begin() + 1, thrust::not2(pred));
// shift input one to the right and initialize segments with init
thrust::detail::raw_buffer<OutputType,Space> temp(n);
thrust::replace_copy_if(first1, last1, flags.begin() + 1, temp.begin() + 1, thrust::negate<HeadFlagType>(), init);
temp[0] = init;
// scan key-flag tuples,
// For additional details refer to Section 2 of the following paper
// S. Sengupta, M. Harris, and M. Garland. "Efficient parallel scan algorithms for GPUs"
// NVIDIA Technical Report NVR-2008-003, December 2008
// http://mgarland.org/files/papers/nvr-2008-003.pdf
thrust::inclusive_scan(thrust::make_zip_iterator(thrust::make_tuple(temp.begin(), flags.begin())),
thrust::make_zip_iterator(thrust::make_tuple(temp.end(), flags.end())),
thrust::make_zip_iterator(thrust::make_tuple(result, flags.begin())),
detail::segmented_scan_functor<OutputType, HeadFlagType, AssociativeOperator>(binary_op));
}
return result + (last1 - first1);
}
} // end namespace generic
} // end namespace device
} // end namespace detail
} // end namespace thrust
<commit_msg>fix bug in segmented_scan<commit_after>/*
* Copyright 2008-2009 NVIDIA Corporation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <thrust/functional.h>
#include <thrust/transform.h>
#include <thrust/replace.h>
#include <thrust/iterator/zip_iterator.h>
#include <thrust/iterator/iterator_traits.h>
#include <thrust/detail/device/scan.h>
#include <thrust/detail/raw_buffer.h>
namespace thrust
{
namespace detail
{
namespace device
{
namespace generic
{
namespace detail
{
template <typename OutputType, typename HeadFlagType, typename AssociativeOperator>
struct segmented_scan_functor
{
AssociativeOperator binary_op;
typedef typename thrust::tuple<OutputType, HeadFlagType> result_type;
__host__ __device__
segmented_scan_functor(AssociativeOperator _binary_op) : binary_op(_binary_op) {}
__host__ __device__
result_type operator()(result_type a, result_type b)
{
return result_type(thrust::get<1>(b) ? thrust::get<0>(b) : binary_op(thrust::get<0>(a), thrust::get<0>(b)),
thrust::get<1>(a) | thrust::get<1>(b));
}
};
} // end namespace detail
template<typename InputIterator1,
typename InputIterator2,
typename OutputIterator,
typename AssociativeOperator,
typename BinaryPredicate>
OutputIterator inclusive_segmented_scan(InputIterator1 first1,
InputIterator1 last1,
InputIterator2 first2,
OutputIterator result,
AssociativeOperator binary_op,
BinaryPredicate pred)
{
typedef typename thrust::iterator_traits<OutputIterator>::value_type OutputType;
typedef typename thrust::iterator_space<OutputIterator>::type Space;
typedef unsigned int HeadFlagType;
if(first1 != last1)
{
const size_t n = last1 - first1;
// compute head flags
thrust::detail::raw_buffer<HeadFlagType,Space> flags(n);
flags[0] = 1; thrust::transform(first2, first2 + (n - 1), first2 + 1, flags.begin() + 1, thrust::not2(pred));
// scan key-flag tuples,
// For additional details refer to Section 2 of the following paper
// S. Sengupta, M. Harris, and M. Garland. "Efficient parallel scan algorithms for GPUs"
// NVIDIA Technical Report NVR-2008-003, December 2008
// http://mgarland.org/files/papers/nvr-2008-003.pdf
thrust::detail::device::inclusive_scan
(thrust::make_zip_iterator(thrust::make_tuple(first1, flags.begin())),
thrust::make_zip_iterator(thrust::make_tuple(last1, flags.end())),
thrust::make_zip_iterator(thrust::make_tuple(result, flags.begin())),
detail::segmented_scan_functor<OutputType, HeadFlagType, AssociativeOperator>(binary_op));
}
return result + (last1 - first1);
}
template<typename InputIterator1,
typename InputIterator2,
typename OutputIterator,
typename T,
typename AssociativeOperator,
typename BinaryPredicate>
OutputIterator exclusive_segmented_scan(InputIterator1 first1,
InputIterator1 last1,
InputIterator2 first2,
OutputIterator result,
const T init,
AssociativeOperator binary_op,
BinaryPredicate pred)
{
typedef typename thrust::iterator_traits<OutputIterator>::value_type OutputType;
typedef typename thrust::iterator_space<OutputIterator>::type Space;
typedef unsigned int HeadFlagType;
if(first1 != last1)
{
const size_t n = last1 - first1;
InputIterator2 last2 = first2 + n;
// compute head flags
thrust::detail::raw_buffer<HeadFlagType,Space> flags(n);
flags[0] = 1; thrust::transform(first2, last2 - 1, first2 + 1, flags.begin() + 1, thrust::not2(pred));
// shift input one to the right and initialize segments with init
thrust::detail::raw_buffer<OutputType,Space> temp(n);
thrust::replace_copy_if(first1, last1 - 1, flags.begin() + 1, temp.begin() + 1, thrust::negate<HeadFlagType>(), init);
temp[0] = init;
// scan key-flag tuples,
// For additional details refer to Section 2 of the following paper
// S. Sengupta, M. Harris, and M. Garland. "Efficient parallel scan algorithms for GPUs"
// NVIDIA Technical Report NVR-2008-003, December 2008
// http://mgarland.org/files/papers/nvr-2008-003.pdf
thrust::inclusive_scan(thrust::make_zip_iterator(thrust::make_tuple(temp.begin(), flags.begin())),
thrust::make_zip_iterator(thrust::make_tuple(temp.end(), flags.end())),
thrust::make_zip_iterator(thrust::make_tuple(result, flags.begin())),
detail::segmented_scan_functor<OutputType, HeadFlagType, AssociativeOperator>(binary_op));
}
return result + (last1 - first1);
}
} // end namespace generic
} // end namespace device
} // end namespace detail
} // end namespace thrust
<|endoftext|> |
<commit_before>
#include <Onsang/utility.hpp>
#include <Onsang/Log.hpp>
#include <Onsang/asio.hpp>
#include <Onsang/serialization.hpp>
#include <Onsang/Net/CmdStreamer.hpp>
#include <Hord/Error.hpp>
#include <Hord/ErrorCode.hpp>
#include <duct/IO/arithmetic.hpp>
#include <cassert>
#include <limits>
#include <mutex>
#include <iomanip>
#include <iostream>
#include <Onsang/detail/gr_ceformat.hpp>
namespace Onsang {
namespace Net {
// class CmdStreamer implementation
#define ONSANG_SCOPE_CLASS Net::CmdStreamer
namespace {
enum : unsigned {
// uint32 size
// uint32 type
msg_header_size = 8u,
// stage : 8
// cmd : 24
mask_type_stage = 0x000000FF,
mask_type_cmd = 0xFFFFFF00
};
static constexpr ceformat::Format const
s_err_command_type_invalid{
": command type %#08x is invalid\n"
},
s_err_stage_type_invalid{
": stage type %#02x is invalid for command type %#08x\n"
}
;
} // anonymous namespace
#define ONSANG_SCOPE_FUNC read_header
bool
CmdStreamer::read_header() {
std::istream stream{&m_streambuf_in};
std::size_t const size
= duct::IO::read_arithmetic<uint32_t>(
stream,
duct::Endian::little
);
uint32_t const type
= duct::IO::read_arithmetic<uint32_t>(
stream,
duct::Endian::little
);
if (stream.fail()) {
return false;
} else {
m_incoming_size = size;
m_incoming_type = type;
return true;
}
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC read_stage
bool
CmdStreamer::read_stage() {
auto const command_type = static_cast<Hord::Cmd::Type>(
m_incoming_type & mask_type_cmd
);
auto const stage_type = static_cast<Hord::Cmd::StageType>(
m_incoming_type & mask_type_stage
);
Hord::Cmd::StageUPtr stage_uptr;
Hord::Cmd::type_info const* const
type_info = m_driver.get_command_type_info(
command_type
);
if (!type_info) {
Log::acquire(Log::error)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ceformat::write_sentinel<
s_err_command_type_invalid
>(
enum_cast(command_type)
)
;
return false;
}
try {
stage_uptr.reset(type_info->construct_stage(stage_type));
std::istream stream{&m_streambuf_in};
auto ser = make_input_serializer(stream);
ser(*stage_uptr);
} catch (Hord::Error& ex) {
stage_uptr.reset();
switch (ex.get_code()) {
case Hord::ErrorCode::cmd_construct_stage_type_invalid:
Log::acquire(Log::error)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ceformat::write_sentinel<s_err_stage_type_invalid>(
enum_cast(stage_type),
enum_cast(command_type)
)
;
return false;
// IO error or malformed data
default:
return false;
}
} catch (...) {
throw;
}
std::size_t const remaining = m_streambuf_in.get_remaining();
if (0u < remaining) {
Log::acquire(Log::debug)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ": "
<< remaining
<< " bytes left in buffer after stage deserialization\n"
;
}
{
std::lock_guard<std::mutex> m_lock{m_stage_buffer_mutex};
m_stage_buffer.emplace_back(std::move(stage_uptr));
m_sig_have_stages.store(true);
}
return true;
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC chain_read_header
void
CmdStreamer::chain_read_header() {
m_incoming_size = 0u;
assert(m_streambuf_in.reset(msg_header_size));
asio::async_read(
m_socket,
asio::buffer(
m_streambuf_in.get_buffer().data(),
msg_header_size
),
asio::transfer_exactly(msg_header_size),
[this](
boost::system::error_code const ec,
std::size_t /*length*/
) {
if (!ec) {
m_streambuf_in.commit_direct(msg_header_size);
read_header();
chain_read_stage();
} else {
halt();
}
}
);
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC chain_read_stage
void
CmdStreamer::chain_read_stage() {
assert(0u < m_incoming_size);
assert(0u != m_incoming_type);
assert(m_streambuf_in.reset(m_incoming_size));
asio::async_read(
m_socket,
asio::buffer(
m_streambuf_in.get_buffer().data(),
m_incoming_size
),
asio::transfer_exactly(m_incoming_size),
[this](
boost::system::error_code const ec,
std::size_t /*length*/
) {
if (!ec) {
m_streambuf_in.commit_direct(m_incoming_size);
read_stage();
chain_read_header();
} else {
halt();
}
}
);
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC chain_flush_output
void
CmdStreamer::chain_flush_output() {
assert(0u < m_outgoing_size);
asio::async_write(
m_socket,
asio::buffer(
make_const(m_streambuf_out).get_buffer().data(),
m_outgoing_size
),
asio::transfer_exactly(m_incoming_size),
[this](
boost::system::error_code const ec,
std::size_t /*length*/
) {
m_sig_pending_output.store(false);
m_outgoing_size = 0u;
if (ec) {
halt();
}
}
);
}
#undef ONSANG_SCOPE_FUNC
// operations
void
CmdStreamer::halt() noexcept {
m_socket.get_io_service().stop();
}
#define ONSANG_SCOPE_FUNC run
void
CmdStreamer::run() {
auto& io_service = m_socket.get_io_service();
try {
while (!io_service.stopped()) {
chain_read_header();
io_service.run();
}
} catch (std::exception& ex) {
Log::acquire(Log::error)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ": caught exception from io_service::run(): "
<< ex.what()
<< "\n"
;
throw;
}
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC context_input
bool
CmdStreamer::context_input(
Hord::System::Context& context
) {
if (!m_sig_have_stages.load()) {
return false;
}
{
std::lock_guard<std::mutex> m_lock{m_stage_buffer_mutex};
for (auto& stage_uptr : m_stage_buffer) {
context.push_input(stage_uptr);
}
m_stage_buffer.clear();
m_sig_have_stages.store(false);
}
return true;
}
#undef ONSANG_SCOPE_FUNC
// TODO: What should the exception specifications for this be?
// Does it leave it up to the callee? Seems to be the intention.
#define ONSANG_SCOPE_FUNC context_output
bool
CmdStreamer::context_output(
Hord::System::Context& context
) {
if (
0 == context.get_output().size() ||
m_sig_pending_output.load()
) {
return false;
}
m_streambuf_out.reset(
msg_header_size + (m_streambuf_out.get_max_size() >> 2)
);
std::ostream stream{&m_streambuf_out};
auto ser = make_output_serializer(stream);
// Seek past header to reserve it; we need the size of the
// stage payload
stream.seekp(msg_header_size);
// data
auto& stage = *context.get_output().front();
ser(stage);
// Can't use buffer.size() later because it might've grown
// beyond our write amount
m_outgoing_size = m_streambuf_out.get_sequence_size();
// header
stream.seekp(0);
std::size_t const h_size = m_outgoing_size - msg_header_size;
assert(std::numeric_limits<uint32_t>::max() >= h_size);
ser(static_cast<uint32_t>(h_size));
uint32_t const h_type
= enum_cast(stage.get_stage_type())
| enum_cast(stage.get_command_type())
;
ser(h_type);
if (stream.fail()) {
return false;
}
m_streambuf_out.commit();
context.get_output().pop_front();
m_sig_pending_output.store(true);
m_socket.get_io_service().post(
[this]() {
chain_flush_output();
}
);
return true;
}
#undef ONSANG_SCOPE_FUNC
#undef ONSANG_SCOPE_CLASS // Onsang::Net::CmdStreamer
} // namespace Net
} // namespace Onsang
<commit_msg>Prefixed all uses of fixed-size integral types with `std::`.<commit_after>
#include <Onsang/utility.hpp>
#include <Onsang/Log.hpp>
#include <Onsang/asio.hpp>
#include <Onsang/serialization.hpp>
#include <Onsang/Net/CmdStreamer.hpp>
#include <Hord/Error.hpp>
#include <Hord/ErrorCode.hpp>
#include <duct/IO/arithmetic.hpp>
#include <cassert>
#include <limits>
#include <mutex>
#include <iomanip>
#include <iostream>
#include <Onsang/detail/gr_ceformat.hpp>
namespace Onsang {
namespace Net {
// class CmdStreamer implementation
#define ONSANG_SCOPE_CLASS Net::CmdStreamer
namespace {
enum : unsigned {
// uint32 size
// uint32 type
msg_header_size = 8u,
// stage : 8
// cmd : 24
mask_type_stage = 0x000000FF,
mask_type_cmd = 0xFFFFFF00
};
static constexpr ceformat::Format const
s_err_command_type_invalid{
": command type %#08x is invalid\n"
},
s_err_stage_type_invalid{
": stage type %#02x is invalid for command type %#08x\n"
}
;
} // anonymous namespace
#define ONSANG_SCOPE_FUNC read_header
bool
CmdStreamer::read_header() {
std::istream stream{&m_streambuf_in};
std::size_t const size
= duct::IO::read_arithmetic<std::uint32_t>(
stream,
duct::Endian::little
);
std::uint32_t const type
= duct::IO::read_arithmetic<std::uint32_t>(
stream,
duct::Endian::little
);
if (stream.fail()) {
return false;
} else {
m_incoming_size = size;
m_incoming_type = type;
return true;
}
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC read_stage
bool
CmdStreamer::read_stage() {
auto const command_type = static_cast<Hord::Cmd::Type>(
m_incoming_type & mask_type_cmd
);
auto const stage_type = static_cast<Hord::Cmd::StageType>(
m_incoming_type & mask_type_stage
);
Hord::Cmd::StageUPtr stage_uptr;
Hord::Cmd::type_info const* const
type_info = m_driver.get_command_type_info(
command_type
);
if (!type_info) {
Log::acquire(Log::error)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ceformat::write_sentinel<
s_err_command_type_invalid
>(
enum_cast(command_type)
)
;
return false;
}
try {
stage_uptr.reset(type_info->construct_stage(stage_type));
std::istream stream{&m_streambuf_in};
auto ser = make_input_serializer(stream);
ser(*stage_uptr);
} catch (Hord::Error& ex) {
stage_uptr.reset();
switch (ex.get_code()) {
case Hord::ErrorCode::cmd_construct_stage_type_invalid:
Log::acquire(Log::error)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ceformat::write_sentinel<s_err_stage_type_invalid>(
enum_cast(stage_type),
enum_cast(command_type)
)
;
return false;
// IO error or malformed data
default:
return false;
}
} catch (...) {
throw;
}
std::size_t const remaining = m_streambuf_in.get_remaining();
if (0u < remaining) {
Log::acquire(Log::debug)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ": "
<< remaining
<< " bytes left in buffer after stage deserialization\n"
;
}
{
std::lock_guard<std::mutex> m_lock{m_stage_buffer_mutex};
m_stage_buffer.emplace_back(std::move(stage_uptr));
m_sig_have_stages.store(true);
}
return true;
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC chain_read_header
void
CmdStreamer::chain_read_header() {
m_incoming_size = 0u;
assert(m_streambuf_in.reset(msg_header_size));
asio::async_read(
m_socket,
asio::buffer(
m_streambuf_in.get_buffer().data(),
msg_header_size
),
asio::transfer_exactly(msg_header_size),
[this](
boost::system::error_code const ec,
std::size_t /*length*/
) {
if (!ec) {
m_streambuf_in.commit_direct(msg_header_size);
read_header();
chain_read_stage();
} else {
halt();
}
}
);
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC chain_read_stage
void
CmdStreamer::chain_read_stage() {
assert(0u < m_incoming_size);
assert(0u != m_incoming_type);
assert(m_streambuf_in.reset(m_incoming_size));
asio::async_read(
m_socket,
asio::buffer(
m_streambuf_in.get_buffer().data(),
m_incoming_size
),
asio::transfer_exactly(m_incoming_size),
[this](
boost::system::error_code const ec,
std::size_t /*length*/
) {
if (!ec) {
m_streambuf_in.commit_direct(m_incoming_size);
read_stage();
chain_read_header();
} else {
halt();
}
}
);
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC chain_flush_output
void
CmdStreamer::chain_flush_output() {
assert(0u < m_outgoing_size);
asio::async_write(
m_socket,
asio::buffer(
make_const(m_streambuf_out).get_buffer().data(),
m_outgoing_size
),
asio::transfer_exactly(m_incoming_size),
[this](
boost::system::error_code const ec,
std::size_t /*length*/
) {
m_sig_pending_output.store(false);
m_outgoing_size = 0u;
if (ec) {
halt();
}
}
);
}
#undef ONSANG_SCOPE_FUNC
// operations
void
CmdStreamer::halt() noexcept {
m_socket.get_io_service().stop();
}
#define ONSANG_SCOPE_FUNC run
void
CmdStreamer::run() {
auto& io_service = m_socket.get_io_service();
try {
while (!io_service.stopped()) {
chain_read_header();
io_service.run();
}
} catch (std::exception& ex) {
Log::acquire(Log::error)
<< ONSANG_SCOPE_FQN_STR_LIT
<< ": caught exception from io_service::run(): "
<< ex.what()
<< "\n"
;
throw;
}
}
#undef ONSANG_SCOPE_FUNC
#define ONSANG_SCOPE_FUNC context_input
bool
CmdStreamer::context_input(
Hord::System::Context& context
) {
if (!m_sig_have_stages.load()) {
return false;
}
{
std::lock_guard<std::mutex> m_lock{m_stage_buffer_mutex};
for (auto& stage_uptr : m_stage_buffer) {
context.push_input(stage_uptr);
}
m_stage_buffer.clear();
m_sig_have_stages.store(false);
}
return true;
}
#undef ONSANG_SCOPE_FUNC
// TODO: What should the exception specifications for this be?
// Does it leave it up to the callee? Seems to be the intention.
#define ONSANG_SCOPE_FUNC context_output
bool
CmdStreamer::context_output(
Hord::System::Context& context
) {
if (
0 == context.get_output().size() ||
m_sig_pending_output.load()
) {
return false;
}
m_streambuf_out.reset(
msg_header_size + (m_streambuf_out.get_max_size() >> 2)
);
std::ostream stream{&m_streambuf_out};
auto ser = make_output_serializer(stream);
// Seek past header to reserve it; we need the size of the
// stage payload
stream.seekp(msg_header_size);
// data
auto& stage = *context.get_output().front();
ser(stage);
// Can't use buffer.size() later because it might've grown
// beyond our write amount
m_outgoing_size = m_streambuf_out.get_sequence_size();
// header
stream.seekp(0);
std::size_t const h_size = m_outgoing_size - msg_header_size;
assert(std::numeric_limits<std::uint32_t>::max() >= h_size);
ser(static_cast<std::uint32_t>(h_size));
std::uint32_t const h_type
= enum_cast(stage.get_stage_type())
| enum_cast(stage.get_command_type())
;
ser(h_type);
if (stream.fail()) {
return false;
}
m_streambuf_out.commit();
context.get_output().pop_front();
m_sig_pending_output.store(true);
m_socket.get_io_service().post(
[this]() {
chain_flush_output();
}
);
return true;
}
#undef ONSANG_SCOPE_FUNC
#undef ONSANG_SCOPE_CLASS // Onsang::Net::CmdStreamer
} // namespace Net
} // namespace Onsang
<|endoftext|> |
<commit_before>/*
* This file is open source software, licensed to you under the terms
* of the Apache License, Version 2.0 (the "License"). See the NOTICE file
* distributed with this work for additional information regarding copyright
* ownership. You may not use this file except in compliance with the License.
*
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing,
* software distributed under the License is distributed on an
* "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
* KIND, either express or implied. See the License for the
* specific language governing permissions and limitations
* under the License.
*/
/*
* Copyright (C) 2014 Cloudius Systems, Ltd.
*/
#ifndef TEMPORARY_BUFFER_HH_
#define TEMPORARY_BUFFER_HH_
#include "deleter.hh"
#include "util/eclipse.hh"
#include <malloc.h>
/// \addtogroup memory-module
/// @{
/// Temporary, self-managed byte buffer.
///
/// A \c temporary_buffer is similar to an \c std::string or a \c std::unique_ptr<char[]>,
/// but provides more flexible memory management. A \c temporary_buffer can own the memory
/// it points to, or it can be shared with another \c temporary_buffer, or point at a substring
/// of a buffer. It uses a \ref deleter to manage its memory.
///
/// A \c temporary_buffer should not be held indefinitely. It can be held while a request
/// is processed, or for a similar duration, but not longer, as it can tie up more memory
/// that its size indicates.
///
/// A buffer can be shared: two \c temporary_buffer objects will point to the same data,
/// or a subset of it. See the \ref temporary_buffer::share() method.
///
/// Unless you created a \c temporary_buffer yourself, do not modify its contents, as they
/// may be shared with another user that does not expect the data to change.
///
/// Use cases for a \c temporary_buffer include:
/// - passing a substring of a tcp packet for the user to consume (zero-copy
/// tcp input)
/// - passing a refcounted blob held in memory to tcp, ensuring that when the TCP ACK
/// is received, the blob is released (by decrementing its reference count) (zero-copy
/// tcp output)
///
/// \tparam CharType underlying character type (must be a variant of \c char).
template <typename CharType>
class temporary_buffer {
static_assert(sizeof(CharType) == 1, "must buffer stream of bytes");
CharType* _buffer;
size_t _size;
deleter _deleter;
public:
/// Creates a \c temporary_buffer of a specified size. The buffer is not shared
/// with anyone, and is not initialized.
///
/// \param size buffer size, in bytes
explicit temporary_buffer(size_t size)
: _buffer(static_cast<CharType*>(malloc(size * sizeof(CharType)))), _size(size)
, _deleter(make_free_deleter(_buffer)) {
if (size && !_buffer) {
throw std::bad_alloc();
}
}
//explicit temporary_buffer(CharType* borrow, size_t size) : _buffer(borrow), _size(size) {}
/// Creates an empty \c temporary_buffer that does not point at anything.
temporary_buffer()
: _buffer(nullptr)
, _size(0) {}
temporary_buffer(const temporary_buffer&) = delete;
/// Moves a \c temporary_buffer.
temporary_buffer(temporary_buffer&& x) noexcept : _buffer(x._buffer), _size(x._size), _deleter(std::move(x._deleter)) {
x._buffer = nullptr;
x._size = 0;
}
/// Creates a \c temporary_buffer with a specific deleter.
///
/// \param buf beginning of the buffer held by this \c temporary_buffer
/// \param size size of the buffer
/// \param d deleter controlling destruction of the buffer. The deleter
/// will be destroyed when there are no longer any users for the buffer.
temporary_buffer(CharType* buf, size_t size, deleter d)
: _buffer(buf), _size(size), _deleter(std::move(d)) {}
void operator=(const temporary_buffer&) = delete;
/// Moves a \c temporary_buffer.
temporary_buffer& operator=(temporary_buffer&& x) {
if (this != &x) {
_buffer = x._buffer;
_size = x._size;
_deleter = std::move(x._deleter);
x._buffer = nullptr;
x._size = 0;
}
return *this;
}
/// Gets a pointer to the beginning of the buffer.
const CharType* get() const { return _buffer; }
/// Gets a writable pointer to the beginning of the buffer. Use only
/// when you are certain no user expects the buffer data not to change.
CharType* get_write() { return _buffer; }
/// Gets the buffer size.
size_t size() const { return _size; }
/// Gets a pointer to the beginning of the buffer.
const CharType* begin() { return _buffer; }
/// Gets a pointer to the end of the buffer.
const CharType* end() { return _buffer + _size; }
/// Returns the buffer, but with a reduced size. The original
/// buffer is consumed by this call and can no longer be used.
///
/// \param size New size; must be smaller than current size.
/// \return the same buffer, with a prefix removed.
temporary_buffer prefix(size_t size) && {
auto ret = std::move(*this);
ret._size = size;
return ret;
}
/// Reads a character from a specific position in the buffer.
///
/// \param pos position to read character from; must be less than size.
CharType operator[](size_t pos) const {
return _buffer[pos];
}
/// Checks whether the buffer is empty.
bool empty() const { return !size(); }
/// Checks whether the buffer is not empty.
operator bool() { return size(); }
/// Create a new \c temporary_buffer object referring to the same
/// underlying data. The underlying \ref deleter will not be destroyed
/// until both the original and the clone have been destroyed.
///
/// \return a clone of the buffer object.
temporary_buffer share() {
return temporary_buffer(_buffer, _size, _deleter.share());
}
/// Create a new \c temporary_buffer object referring to a substring of the
/// same underlying data. The underlying \ref deleter will not be destroyed
/// until both the original and the clone have been destroyed.
///
/// \param pos Position of the first character to share.
/// \param len Length of substring to share.
/// \return a clone of the buffer object, referring to a substring.
temporary_buffer share(size_t pos, size_t len) {
auto ret = share();
ret._buffer += pos;
ret._size = len;
return ret;
}
/// Remove a prefix from the buffer. The underlying data
/// is not modified.
///
/// \param pos Position of first character to retain.
void trim_front(size_t pos) {
_buffer += pos;
_size -= pos;
}
/// Remove a suffix from the buffer. The underlying data
/// is not modified.
///
/// \param pos Position of first character to drop.
void trim(size_t pos) {
_size = pos;
}
/// Stops automatic memory management. When the \c temporary_buffer
/// object is destroyed, the underlying \ref deleter will not be called.
/// Instead, it is the caller's responsibility to destroy the deleter object
/// when the data is no longer needed.
///
/// \return \ref deleter object managing the data's lifetime.
deleter release() {
return std::move(_deleter);
}
/// Creates a \c temporary_buffer object with a specified size, with
/// memory aligned to a specific boundary.
///
/// \param alignment Required alignment; must be a power of two.
/// \param size Required size.
/// \return a new \c temporary_buffer object.
static temporary_buffer aligned(size_t alignment, size_t size) {
void *ptr = nullptr;
auto ret = ::posix_memalign(&ptr, alignment, size * sizeof(CharType));
auto buf = static_cast<CharType*>(ptr);
if (ret) {
throw std::bad_alloc();
}
return temporary_buffer(buf, size, make_free_deleter(buf));
}
};
/// @}
#endif /* TEMPORARY_BUFFER_HH_ */
<commit_msg>temporary_buffer: make operator bool explicit (and const)<commit_after>/*
* This file is open source software, licensed to you under the terms
* of the Apache License, Version 2.0 (the "License"). See the NOTICE file
* distributed with this work for additional information regarding copyright
* ownership. You may not use this file except in compliance with the License.
*
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing,
* software distributed under the License is distributed on an
* "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
* KIND, either express or implied. See the License for the
* specific language governing permissions and limitations
* under the License.
*/
/*
* Copyright (C) 2014 Cloudius Systems, Ltd.
*/
#ifndef TEMPORARY_BUFFER_HH_
#define TEMPORARY_BUFFER_HH_
#include "deleter.hh"
#include "util/eclipse.hh"
#include <malloc.h>
/// \addtogroup memory-module
/// @{
/// Temporary, self-managed byte buffer.
///
/// A \c temporary_buffer is similar to an \c std::string or a \c std::unique_ptr<char[]>,
/// but provides more flexible memory management. A \c temporary_buffer can own the memory
/// it points to, or it can be shared with another \c temporary_buffer, or point at a substring
/// of a buffer. It uses a \ref deleter to manage its memory.
///
/// A \c temporary_buffer should not be held indefinitely. It can be held while a request
/// is processed, or for a similar duration, but not longer, as it can tie up more memory
/// that its size indicates.
///
/// A buffer can be shared: two \c temporary_buffer objects will point to the same data,
/// or a subset of it. See the \ref temporary_buffer::share() method.
///
/// Unless you created a \c temporary_buffer yourself, do not modify its contents, as they
/// may be shared with another user that does not expect the data to change.
///
/// Use cases for a \c temporary_buffer include:
/// - passing a substring of a tcp packet for the user to consume (zero-copy
/// tcp input)
/// - passing a refcounted blob held in memory to tcp, ensuring that when the TCP ACK
/// is received, the blob is released (by decrementing its reference count) (zero-copy
/// tcp output)
///
/// \tparam CharType underlying character type (must be a variant of \c char).
template <typename CharType>
class temporary_buffer {
static_assert(sizeof(CharType) == 1, "must buffer stream of bytes");
CharType* _buffer;
size_t _size;
deleter _deleter;
public:
/// Creates a \c temporary_buffer of a specified size. The buffer is not shared
/// with anyone, and is not initialized.
///
/// \param size buffer size, in bytes
explicit temporary_buffer(size_t size)
: _buffer(static_cast<CharType*>(malloc(size * sizeof(CharType)))), _size(size)
, _deleter(make_free_deleter(_buffer)) {
if (size && !_buffer) {
throw std::bad_alloc();
}
}
//explicit temporary_buffer(CharType* borrow, size_t size) : _buffer(borrow), _size(size) {}
/// Creates an empty \c temporary_buffer that does not point at anything.
temporary_buffer()
: _buffer(nullptr)
, _size(0) {}
temporary_buffer(const temporary_buffer&) = delete;
/// Moves a \c temporary_buffer.
temporary_buffer(temporary_buffer&& x) noexcept : _buffer(x._buffer), _size(x._size), _deleter(std::move(x._deleter)) {
x._buffer = nullptr;
x._size = 0;
}
/// Creates a \c temporary_buffer with a specific deleter.
///
/// \param buf beginning of the buffer held by this \c temporary_buffer
/// \param size size of the buffer
/// \param d deleter controlling destruction of the buffer. The deleter
/// will be destroyed when there are no longer any users for the buffer.
temporary_buffer(CharType* buf, size_t size, deleter d)
: _buffer(buf), _size(size), _deleter(std::move(d)) {}
void operator=(const temporary_buffer&) = delete;
/// Moves a \c temporary_buffer.
temporary_buffer& operator=(temporary_buffer&& x) {
if (this != &x) {
_buffer = x._buffer;
_size = x._size;
_deleter = std::move(x._deleter);
x._buffer = nullptr;
x._size = 0;
}
return *this;
}
/// Gets a pointer to the beginning of the buffer.
const CharType* get() const { return _buffer; }
/// Gets a writable pointer to the beginning of the buffer. Use only
/// when you are certain no user expects the buffer data not to change.
CharType* get_write() { return _buffer; }
/// Gets the buffer size.
size_t size() const { return _size; }
/// Gets a pointer to the beginning of the buffer.
const CharType* begin() { return _buffer; }
/// Gets a pointer to the end of the buffer.
const CharType* end() { return _buffer + _size; }
/// Returns the buffer, but with a reduced size. The original
/// buffer is consumed by this call and can no longer be used.
///
/// \param size New size; must be smaller than current size.
/// \return the same buffer, with a prefix removed.
temporary_buffer prefix(size_t size) && {
auto ret = std::move(*this);
ret._size = size;
return ret;
}
/// Reads a character from a specific position in the buffer.
///
/// \param pos position to read character from; must be less than size.
CharType operator[](size_t pos) const {
return _buffer[pos];
}
/// Checks whether the buffer is empty.
bool empty() const { return !size(); }
/// Checks whether the buffer is not empty.
explicit operator bool() const { return size(); }
/// Create a new \c temporary_buffer object referring to the same
/// underlying data. The underlying \ref deleter will not be destroyed
/// until both the original and the clone have been destroyed.
///
/// \return a clone of the buffer object.
temporary_buffer share() {
return temporary_buffer(_buffer, _size, _deleter.share());
}
/// Create a new \c temporary_buffer object referring to a substring of the
/// same underlying data. The underlying \ref deleter will not be destroyed
/// until both the original and the clone have been destroyed.
///
/// \param pos Position of the first character to share.
/// \param len Length of substring to share.
/// \return a clone of the buffer object, referring to a substring.
temporary_buffer share(size_t pos, size_t len) {
auto ret = share();
ret._buffer += pos;
ret._size = len;
return ret;
}
/// Remove a prefix from the buffer. The underlying data
/// is not modified.
///
/// \param pos Position of first character to retain.
void trim_front(size_t pos) {
_buffer += pos;
_size -= pos;
}
/// Remove a suffix from the buffer. The underlying data
/// is not modified.
///
/// \param pos Position of first character to drop.
void trim(size_t pos) {
_size = pos;
}
/// Stops automatic memory management. When the \c temporary_buffer
/// object is destroyed, the underlying \ref deleter will not be called.
/// Instead, it is the caller's responsibility to destroy the deleter object
/// when the data is no longer needed.
///
/// \return \ref deleter object managing the data's lifetime.
deleter release() {
return std::move(_deleter);
}
/// Creates a \c temporary_buffer object with a specified size, with
/// memory aligned to a specific boundary.
///
/// \param alignment Required alignment; must be a power of two.
/// \param size Required size.
/// \return a new \c temporary_buffer object.
static temporary_buffer aligned(size_t alignment, size_t size) {
void *ptr = nullptr;
auto ret = ::posix_memalign(&ptr, alignment, size * sizeof(CharType));
auto buf = static_cast<CharType*>(ptr);
if (ret) {
throw std::bad_alloc();
}
return temporary_buffer(buf, size, make_free_deleter(buf));
}
};
/// @}
#endif /* TEMPORARY_BUFFER_HH_ */
<|endoftext|> |
<commit_before>extern "C" {
#include "bin/src/halide_hexagon_remote.h"
#include <memory.h>
#include <stdlib.h>
#include <stdio.h>
#include <dlfcn.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include "HAP_farf.h"
#include "HAP_power.h"
}
#include <HalideRuntime.h>
#include <qurt.h>
#include "elf.h"
#include "pipeline_context.h"
#include "log.h"
const int stack_alignment = 128;
const int stack_size = 1024 * 1024;
typedef halide_hexagon_remote_handle_t handle_t;
typedef halide_hexagon_remote_buffer buffer;
// Use a 64 KB circular buffer to store log messages.
Log global_log(1024 * 64);
void log_printf(const char *fmt, ...) {
char message[1024] = { 0, };
va_list ap;
va_start(ap, fmt);
int message_size = vsnprintf(message, sizeof(message) - 1, fmt, ap);
va_end(ap);
global_log.write(message, message_size);
}
extern "C" {
// This is a basic implementation of the Halide runtime for Hexagon.
void halide_print(void *user_context, const char *str) {
log_printf("%s", str);
}
void halide_error(void *user_context, const char *str) {
halide_print(user_context, str);
}
void *halide_malloc(void *user_context, size_t x) {
return memalign(128, x);
}
void halide_free(void *user_context, void *ptr) {
free(ptr);
}
void *halide_get_symbol(const char *name) {
return dlsym(RTLD_DEFAULT, name);
}
void *halide_load_library(const char *name) {
return dlopen(name, RTLD_LAZY);
}
void *halide_get_library_symbol(void *lib, const char *name) {
return dlsym(lib, name);
}
typedef int (*set_runtime_t)(halide_malloc_t user_malloc,
halide_free_t custom_free,
halide_print_t print,
halide_error_handler_t error_handler,
halide_do_par_for_t do_par_for,
halide_do_task_t do_task,
void *(*)(const char *),
void *(*)(const char *),
void *(*)(void *, const char *));
int context_count = 0;
PipelineContext run_context(stack_alignment, stack_size);
int halide_hexagon_remote_initialize_kernels(const unsigned char *code, int codeLen,
handle_t *module_ptr) {
elf_t *lib = obj_dlopen_mem(code, codeLen);
if (!lib) {
log_printf("dlopen failed");
return -1;
}
// Initialize the runtime. The Hexagon runtime can't call any
// system functions (because we can't link them), so we put all
// the implementations that need to do so here, and pass poiners
// to them in here.
set_runtime_t set_runtime = (set_runtime_t)obj_dlsym(lib, "halide_noos_set_runtime");
if (!set_runtime) {
obj_dlclose(lib);
log_printf("halide_noos_set_runtime not found in shared object\n");
return -1;
}
int result = set_runtime(halide_malloc,
halide_free,
halide_print,
halide_error,
halide_do_par_for,
halide_do_task,
halide_get_symbol,
halide_load_library,
halide_get_library_symbol);
if (result != 0) {
obj_dlclose(lib);
log_printf("set_runtime failed (%d)\n", result);
return result;
}
*module_ptr = reinterpret_cast<handle_t>(lib);
if (context_count == 0) {
HAP_power_request_t request;
request.type = HAP_power_set_apptype;
request.apptype = HAP_POWER_COMPUTE_CLIENT_CLASS;
int retval = HAP_power_set(NULL, &request);
if (0 != retval) {
log_printf("HAP_power_set(HAP_power_set_apptype) failed (%d)\n", retval);
return -1;
}
request.type = HAP_power_set_HVX;
request.hvx.power_up = TRUE;
retval = HAP_power_set(NULL, &request);
if (0 != retval) {
log_printf("HAP_power_set(HAP_power_set_HVX) failed (%d)\n", retval);
return -1;
}
request.type = HAP_power_set_mips_bw;
request.mips_bw.set_mips = TRUE;
request.mips_bw.mipsPerThread = 500;
request.mips_bw.mipsTotal = 1000;
request.mips_bw.set_bus_bw = TRUE;
request.mips_bw.bwBytePerSec = static_cast<uint64_t>(12000) * 1000000;
request.mips_bw.busbwUsagePercentage = 100;
request.mips_bw.set_latency = TRUE;
request.mips_bw.latency = 1;
retval = HAP_power_set(NULL, &request);
if (0 != retval) {
log_printf("HAP_power_set(HAP_power_set_mips_bw) failed (%d)\n", retval);
return -1;
}
}
context_count++;
return 0;
}
handle_t halide_hexagon_remote_get_symbol(handle_t module_ptr, const char* name, int nameLen) {
return reinterpret_cast<handle_t>(obj_dlsym(reinterpret_cast<elf_t*>(module_ptr), name));
}
int halide_hexagon_remote_run(handle_t module_ptr, handle_t function,
const buffer *input_buffersPtrs, int input_buffersLen,
buffer *output_buffersPtrs, int output_buffersLen,
const buffer *input_scalarsPtrs, int input_scalarsLen) {
// Get a pointer to the argv version of the pipeline.
pipeline_argv_t pipeline = reinterpret_cast<pipeline_argv_t>(function);
// Construct a list of arguments. This is only part of a
// buffer_t. We know that the only field of buffer_t that the
// generated code should access is the host field (any other
// fields should be passed as their own scalar parameters) so we
// can just make this dummy buffer_t type.
struct buffer_t {
uint64_t dev;
uint8_t* host;
};
void **args = (void **)__builtin_alloca((input_buffersLen + input_scalarsLen + output_buffersLen) * sizeof(void *));
buffer_t *buffers = (buffer_t *)__builtin_alloca((input_buffersLen + output_buffersLen) * sizeof(buffer_t));
void **next_arg = &args[0];
buffer_t *next_buffer_t = &buffers[0];
// Input buffers come first.
for (int i = 0; i < input_buffersLen; i++, next_arg++, next_buffer_t++) {
next_buffer_t->host = input_buffersPtrs[i].data;
*next_arg = next_buffer_t;
}
// Output buffers are next.
for (int i = 0; i < output_buffersLen; i++, next_arg++, next_buffer_t++) {
next_buffer_t->host = output_buffersPtrs[i].data;
*next_arg = next_buffer_t;
}
// Input scalars are last.
for (int i = 0; i < input_scalarsLen; i++, next_arg++) {
*next_arg = input_scalarsPtrs[i].data;
}
// Call the pipeline and return the result.
return run_context.run(pipeline, args);
}
int halide_hexagon_remote_poll_log(char *out, int size, int *read_size) {
// Leave room for appending a null terminator.
*read_size = global_log.read(out, size - 1);
out[*read_size - 1] = 0;
return 0;
}
int halide_hexagon_remote_release_kernels(handle_t module_ptr, int codeLen) {
obj_dlclose(reinterpret_cast<elf_t*>(module_ptr));
if (context_count-- == 0) {
HAP_power_request(0, 0, -1);
}
return 0;
}
} // extern "C"
<commit_msg>Added preallocated buffer to speed up halide_malloc/free<commit_after>extern "C" {
#include "bin/src/halide_hexagon_remote.h"
#include <memory.h>
#include <stdlib.h>
#include <stdio.h>
#include <dlfcn.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include "HAP_farf.h"
#include "HAP_power.h"
}
#include <HalideRuntime.h>
#include <qurt.h>
#include "elf.h"
#include "pipeline_context.h"
#include "log.h"
const int stack_alignment = 128;
const int stack_size = 1024 * 1024;
typedef halide_hexagon_remote_handle_t handle_t;
typedef halide_hexagon_remote_buffer buffer;
// Use a 64 KB circular buffer to store log messages.
Log global_log(1024 * 64);
void log_printf(const char *fmt, ...) {
char message[1024] = { 0, };
va_list ap;
va_start(ap, fmt);
int message_size = vsnprintf(message, sizeof(message) - 1, fmt, ap);
va_end(ap);
global_log.write(message, message_size);
}
extern "C" {
// This is a basic implementation of the Halide runtime for Hexagon.
void halide_print(void *user_context, const char *str) {
log_printf("%s", str);
}
void halide_error(void *user_context, const char *str) {
halide_print(user_context, str);
}
namespace {
// We keep a small pool of small pre-allocated buffers for use by Halide
// code; some kernels end up doing per-scanline allocations and frees,
// which can cause a noticable performance impact on some workloads.
// 'num_buffers' is the number of pre-allocated buffers and 'buffer_size' is
// the size of each buffer. The pre-allocated buffers are shared among threads
// and we use __sync_val_compare_and_swap primitive to synchronize the buffer
// allocation.
const int num_buffers = 8;
const int buffer_size = 1024 * 64;
int buf_is_used[num_buffers];
char mem_buf[num_buffers][buffer_size]
__attribute__((aligned(128))); /* Hexagon requires 128-byte alignment. */
}
void *halide_malloc(void *user_context, size_t x) {
if (x <= buffer_size) {
for (int i = 0; i < num_buffers; ++i) {
if (__sync_val_compare_and_swap(buf_is_used+i, 0, 1) == 0) {
return mem_buf[i];
}
}
}
return memalign(128, x);
}
void halide_free(void *user_context, void *ptr) {
for (int i = 0; i < num_buffers; ++i) {
if (mem_buf[i] == ptr) {
buf_is_used[i] = 0;
return;
}
}
free(ptr);
}
void *halide_get_symbol(const char *name) {
return dlsym(RTLD_DEFAULT, name);
}
void *halide_load_library(const char *name) {
return dlopen(name, RTLD_LAZY);
}
void *halide_get_library_symbol(void *lib, const char *name) {
return dlsym(lib, name);
}
typedef int (*set_runtime_t)(halide_malloc_t user_malloc,
halide_free_t custom_free,
halide_print_t print,
halide_error_handler_t error_handler,
halide_do_par_for_t do_par_for,
halide_do_task_t do_task,
void *(*)(const char *),
void *(*)(const char *),
void *(*)(void *, const char *));
int context_count = 0;
PipelineContext run_context(stack_alignment, stack_size);
int halide_hexagon_remote_initialize_kernels(const unsigned char *code, int codeLen,
handle_t *module_ptr) {
elf_t *lib = obj_dlopen_mem(code, codeLen);
if (!lib) {
log_printf("dlopen failed");
return -1;
}
// Initialize the runtime. The Hexagon runtime can't call any
// system functions (because we can't link them), so we put all
// the implementations that need to do so here, and pass poiners
// to them in here.
set_runtime_t set_runtime = (set_runtime_t)obj_dlsym(lib, "halide_noos_set_runtime");
if (!set_runtime) {
obj_dlclose(lib);
log_printf("halide_noos_set_runtime not found in shared object\n");
return -1;
}
int result = set_runtime(halide_malloc,
halide_free,
halide_print,
halide_error,
halide_do_par_for,
halide_do_task,
halide_get_symbol,
halide_load_library,
halide_get_library_symbol);
if (result != 0) {
obj_dlclose(lib);
log_printf("set_runtime failed (%d)\n", result);
return result;
}
*module_ptr = reinterpret_cast<handle_t>(lib);
if (context_count == 0) {
HAP_power_request_t request;
request.type = HAP_power_set_apptype;
request.apptype = HAP_POWER_COMPUTE_CLIENT_CLASS;
int retval = HAP_power_set(NULL, &request);
if (0 != retval) {
log_printf("HAP_power_set(HAP_power_set_apptype) failed (%d)\n", retval);
return -1;
}
request.type = HAP_power_set_HVX;
request.hvx.power_up = TRUE;
retval = HAP_power_set(NULL, &request);
if (0 != retval) {
log_printf("HAP_power_set(HAP_power_set_HVX) failed (%d)\n", retval);
return -1;
}
request.type = HAP_power_set_mips_bw;
request.mips_bw.set_mips = TRUE;
request.mips_bw.mipsPerThread = 500;
request.mips_bw.mipsTotal = 1000;
request.mips_bw.set_bus_bw = TRUE;
request.mips_bw.bwBytePerSec = static_cast<uint64_t>(12000) * 1000000;
request.mips_bw.busbwUsagePercentage = 100;
request.mips_bw.set_latency = TRUE;
request.mips_bw.latency = 1;
retval = HAP_power_set(NULL, &request);
if (0 != retval) {
log_printf("HAP_power_set(HAP_power_set_mips_bw) failed (%d)\n", retval);
return -1;
}
}
context_count++;
return 0;
}
handle_t halide_hexagon_remote_get_symbol(handle_t module_ptr, const char* name, int nameLen) {
return reinterpret_cast<handle_t>(obj_dlsym(reinterpret_cast<elf_t*>(module_ptr), name));
}
int halide_hexagon_remote_run(handle_t module_ptr, handle_t function,
const buffer *input_buffersPtrs, int input_buffersLen,
buffer *output_buffersPtrs, int output_buffersLen,
const buffer *input_scalarsPtrs, int input_scalarsLen) {
// Get a pointer to the argv version of the pipeline.
pipeline_argv_t pipeline = reinterpret_cast<pipeline_argv_t>(function);
// Construct a list of arguments. This is only part of a
// buffer_t. We know that the only field of buffer_t that the
// generated code should access is the host field (any other
// fields should be passed as their own scalar parameters) so we
// can just make this dummy buffer_t type.
struct buffer_t {
uint64_t dev;
uint8_t* host;
};
void **args = (void **)__builtin_alloca((input_buffersLen + input_scalarsLen + output_buffersLen) * sizeof(void *));
buffer_t *buffers = (buffer_t *)__builtin_alloca((input_buffersLen + output_buffersLen) * sizeof(buffer_t));
void **next_arg = &args[0];
buffer_t *next_buffer_t = &buffers[0];
// Input buffers come first.
for (int i = 0; i < input_buffersLen; i++, next_arg++, next_buffer_t++) {
next_buffer_t->host = input_buffersPtrs[i].data;
*next_arg = next_buffer_t;
}
// Output buffers are next.
for (int i = 0; i < output_buffersLen; i++, next_arg++, next_buffer_t++) {
next_buffer_t->host = output_buffersPtrs[i].data;
*next_arg = next_buffer_t;
}
// Input scalars are last.
for (int i = 0; i < input_scalarsLen; i++, next_arg++) {
*next_arg = input_scalarsPtrs[i].data;
}
// Call the pipeline and return the result.
return run_context.run(pipeline, args);
}
int halide_hexagon_remote_poll_log(char *out, int size, int *read_size) {
// Leave room for appending a null terminator.
*read_size = global_log.read(out, size - 1);
out[*read_size - 1] = 0;
return 0;
}
int halide_hexagon_remote_release_kernels(handle_t module_ptr, int codeLen) {
obj_dlclose(reinterpret_cast<elf_t*>(module_ptr));
if (context_count-- == 0) {
HAP_power_request(0, 0, -1);
}
return 0;
}
} // extern "C"
<|endoftext|> |
<commit_before>//===-- sanitizer_printf_test.cc ------------------------------------------===//
//
// The LLVM Compiler Infrastructure
//
// This file is distributed under the University of Illinois Open Source
// License. See LICENSE.TXT for details.
//
//===----------------------------------------------------------------------===//
//
// Tests for sanitizer_printf.cc
//
//===----------------------------------------------------------------------===//
#include "sanitizer_common/sanitizer_common.h"
#include "sanitizer_common/sanitizer_libc.h"
#include "gtest/gtest.h"
#include <string.h>
#include <limits.h>
namespace __sanitizer {
TEST(Printf, Basic) {
char buf[1024];
uptr len = internal_snprintf(buf, sizeof(buf),
"a%db%zdc%ue%zuf%xh%zxq%pe%sr",
(int)-1, (long)-2, // NOLINT
(unsigned)-4, (unsigned long)5, // NOLINT
(unsigned)10, (unsigned long)11, // NOLINT
(void*)0x123, "_string_");
EXPECT_EQ(len, strlen(buf));
void *ptr;
if (sizeof(ptr) == 4) {
EXPECT_STREQ("a-1b-2c4294967292e5fahbq"
"0x00000123e_string_r", buf);
} else {
EXPECT_STREQ("a-1b-2c4294967292e5fahbq"
"0x000000000123e_string_r", buf);
}
}
TEST(Printf, OverflowStr) {
char buf[] = "123456789";
uptr len = internal_snprintf(buf, 4, "%s", "abcdef"); // NOLINT
EXPECT_EQ(len, (uptr)6);
EXPECT_STREQ("abc", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
TEST(Printf, OverflowInt) {
char buf[] = "123456789";
internal_snprintf(buf, 4, "%d", -123456789); // NOLINT
EXPECT_STREQ("-12", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
TEST(Printf, OverflowUint) {
char buf[] = "123456789";
uptr val;
if (sizeof(val) == 4) {
val = (uptr)0x12345678;
} else {
val = (uptr)0x123456789ULL;
}
internal_snprintf(buf, 4, "a%zx", val); // NOLINT
EXPECT_STREQ("a12", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
TEST(Printf, OverflowPtr) {
char buf[] = "123456789";
void *p;
if (sizeof(p) == 4) {
p = (void*)0x1234567;
} else {
p = (void*)0x123456789ULL;
}
internal_snprintf(buf, 4, "%p", p); // NOLINT
EXPECT_STREQ("0x0", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
template<typename T>
static void TestAgainstLibc(const char *fmt, T arg1, T arg2) {
char buf[1024];
uptr len = internal_snprintf(buf, sizeof(buf), fmt, arg1, arg2);
char buf2[1024];
snprintf(buf2, sizeof(buf2), fmt, arg1, arg2);
EXPECT_EQ(len, strlen(buf));
EXPECT_STREQ(buf2, buf);
}
TEST(Printf, MinMax) {
TestAgainstLibc<int>("%d-%d", INT_MIN, INT_MAX); // NOLINT
TestAgainstLibc<long>("%zd-%zd", LONG_MIN, LONG_MAX); // NOLINT
TestAgainstLibc<unsigned>("%u-%u", 0, UINT_MAX); // NOLINT
TestAgainstLibc<unsigned long>("%zu-%zu", 0, ULONG_MAX); // NOLINT
TestAgainstLibc<unsigned>("%x-%x", 0, UINT_MAX); // NOLINT
TestAgainstLibc<unsigned long>("%zx-%zx", 0, ULONG_MAX); // NOLINT
Report("%zd\n", LONG_MIN);
}
TEST(Printf, Padding) {
TestAgainstLibc<int>("%3d - %3d", 1, 0);
TestAgainstLibc<int>("%3d - %3d", -1, 123);
TestAgainstLibc<int>("%3d - %3d", -1, -123);
TestAgainstLibc<int>("%3d - %3d", 12, 1234);
TestAgainstLibc<int>("%3d - %3d", -12, -1234);
TestAgainstLibc<int>("%03d - %03d", 1, 0);
TestAgainstLibc<int>("%03d - %03d", -1, 123);
TestAgainstLibc<int>("%03d - %03d", -1, -123);
TestAgainstLibc<int>("%03d - %03d", 12, 1234);
TestAgainstLibc<int>("%03d - %03d", -12, -1234);
}
} // namespace __sanitizer
<commit_msg>tsan: remove debug output from test<commit_after>//===-- sanitizer_printf_test.cc ------------------------------------------===//
//
// The LLVM Compiler Infrastructure
//
// This file is distributed under the University of Illinois Open Source
// License. See LICENSE.TXT for details.
//
//===----------------------------------------------------------------------===//
//
// Tests for sanitizer_printf.cc
//
//===----------------------------------------------------------------------===//
#include "sanitizer_common/sanitizer_common.h"
#include "sanitizer_common/sanitizer_libc.h"
#include "gtest/gtest.h"
#include <string.h>
#include <limits.h>
namespace __sanitizer {
TEST(Printf, Basic) {
char buf[1024];
uptr len = internal_snprintf(buf, sizeof(buf),
"a%db%zdc%ue%zuf%xh%zxq%pe%sr",
(int)-1, (long)-2, // NOLINT
(unsigned)-4, (unsigned long)5, // NOLINT
(unsigned)10, (unsigned long)11, // NOLINT
(void*)0x123, "_string_");
EXPECT_EQ(len, strlen(buf));
void *ptr;
if (sizeof(ptr) == 4) {
EXPECT_STREQ("a-1b-2c4294967292e5fahbq"
"0x00000123e_string_r", buf);
} else {
EXPECT_STREQ("a-1b-2c4294967292e5fahbq"
"0x000000000123e_string_r", buf);
}
}
TEST(Printf, OverflowStr) {
char buf[] = "123456789";
uptr len = internal_snprintf(buf, 4, "%s", "abcdef"); // NOLINT
EXPECT_EQ(len, (uptr)6);
EXPECT_STREQ("abc", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
TEST(Printf, OverflowInt) {
char buf[] = "123456789";
internal_snprintf(buf, 4, "%d", -123456789); // NOLINT
EXPECT_STREQ("-12", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
TEST(Printf, OverflowUint) {
char buf[] = "123456789";
uptr val;
if (sizeof(val) == 4) {
val = (uptr)0x12345678;
} else {
val = (uptr)0x123456789ULL;
}
internal_snprintf(buf, 4, "a%zx", val); // NOLINT
EXPECT_STREQ("a12", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
TEST(Printf, OverflowPtr) {
char buf[] = "123456789";
void *p;
if (sizeof(p) == 4) {
p = (void*)0x1234567;
} else {
p = (void*)0x123456789ULL;
}
internal_snprintf(buf, 4, "%p", p); // NOLINT
EXPECT_STREQ("0x0", buf);
EXPECT_EQ(buf[3], 0);
EXPECT_EQ(buf[4], '5');
EXPECT_EQ(buf[5], '6');
EXPECT_EQ(buf[6], '7');
EXPECT_EQ(buf[7], '8');
EXPECT_EQ(buf[8], '9');
EXPECT_EQ(buf[9], 0);
}
template<typename T>
static void TestAgainstLibc(const char *fmt, T arg1, T arg2) {
char buf[1024];
uptr len = internal_snprintf(buf, sizeof(buf), fmt, arg1, arg2);
char buf2[1024];
snprintf(buf2, sizeof(buf2), fmt, arg1, arg2);
EXPECT_EQ(len, strlen(buf));
EXPECT_STREQ(buf2, buf);
}
TEST(Printf, MinMax) {
TestAgainstLibc<int>("%d-%d", INT_MIN, INT_MAX); // NOLINT
TestAgainstLibc<long>("%zd-%zd", LONG_MIN, LONG_MAX); // NOLINT
TestAgainstLibc<unsigned>("%u-%u", 0, UINT_MAX); // NOLINT
TestAgainstLibc<unsigned long>("%zu-%zu", 0, ULONG_MAX); // NOLINT
TestAgainstLibc<unsigned>("%x-%x", 0, UINT_MAX); // NOLINT
TestAgainstLibc<unsigned long>("%zx-%zx", 0, ULONG_MAX); // NOLINT
}
TEST(Printf, Padding) {
TestAgainstLibc<int>("%3d - %3d", 1, 0);
TestAgainstLibc<int>("%3d - %3d", -1, 123);
TestAgainstLibc<int>("%3d - %3d", -1, -123);
TestAgainstLibc<int>("%3d - %3d", 12, 1234);
TestAgainstLibc<int>("%3d - %3d", -12, -1234);
TestAgainstLibc<int>("%03d - %03d", 1, 0);
TestAgainstLibc<int>("%03d - %03d", -1, 123);
TestAgainstLibc<int>("%03d - %03d", -1, -123);
TestAgainstLibc<int>("%03d - %03d", 12, 1234);
TestAgainstLibc<int>("%03d - %03d", -12, -1234);
}
} // namespace __sanitizer
<|endoftext|> |
<commit_before>
#include <v8.h>
#include "JSSystemStruct.hpp"
#include "JSContextStruct.hpp"
#include "../JSObjects/JSFields.hpp"
#include "../JSEntityCreateInfo.hpp"
#include "JSPositionListener.hpp"
#include "JSPresenceStruct.hpp"
#include "../JSLogging.hpp"
#include "../JSObjectScript.hpp"
namespace Sirikata{
namespace JS{
JSSystemStruct::JSSystemStruct ( JSContextStruct* jscont, Capabilities::CapNum capNum)
: associatedContext(jscont),
mCapNum(capNum)
{
}
v8::Handle<v8::Value> JSSystemStruct::struct_evalInGlobal(const String& native_contents, ScriptOrigin* sOrigin)
{
if (!Capabilities::givesCap(mCapNum, Capabilities::EVAL))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability tocall eval in global directly.")));
return associatedContext->struct_evalInGlobal(native_contents,sOrigin);
}
v8::Handle<v8::Value> JSSystemStruct::getAssociatedPresence()
{
return associatedContext->getAssociatedPresence();
}
v8::Handle<v8::Value> JSSystemStruct::storageBeginTransaction() {
return associatedContext->storageBeginTransaction();
}
v8::Handle<v8::Value> JSSystemStruct::storageCommit(v8::Handle<v8::Function> cb)
{
return associatedContext->storageCommit(cb);
}
v8::Handle<v8::Value> JSSystemStruct::storageWrite(const OH::Storage::Key& key, const String& toWrite, v8::Handle<v8::Function> cb)
{
return associatedContext->storageWrite(key, toWrite, cb);
}
v8::Handle<v8::Value> JSSystemStruct::httpRequest(Sirikata::Network::Address addr, Transfer::HttpManager::HTTP_METHOD method, String request, v8::Persistent<v8::Function> cb)
{
return associatedContext->httpRequest(addr,method,request,cb);
}
v8::Handle<v8::Value> JSSystemStruct::storageErase(const OH::Storage::Key& key, v8::Handle<v8::Function> cb)
{
return associatedContext->storageErase(key, cb);
}
v8::Handle<v8::Value> JSSystemStruct::storageRead(const OH::Storage::Key& key, v8::Handle<v8::Function> cb)
{
return associatedContext->storageRead(key, cb);
}
v8::Handle<v8::Value> JSSystemStruct::sendSandbox(const String& msgToSend, JSContextStruct* destination)
{
return associatedContext->sendSandbox(msgToSend,destination);
}
v8::Handle<v8::Value> JSSystemStruct::setRestoreScript(const String& key, v8::Handle<v8::Function> cb)
{
return associatedContext->setRestoreScript(key, cb);
}
v8::Handle<v8::Value> JSSystemStruct::emersonCompileString(const String& toCompile)
{
return associatedContext->emersonCompileString(toCompile);
}
v8::Handle<v8::Value> JSSystemStruct::checkResources()
{
return v8::Boolean::New(true);
}
v8::Handle<v8::Value> JSSystemStruct::debug_fileWrite(const String& strToWrite,const String& filename)
{
return associatedContext->debug_fileWrite(strToWrite,filename);
}
v8::Handle<v8::Value> JSSystemStruct::debug_fileRead(const String& filename)
{
return associatedContext->debug_fileRead(filename);
}
v8::Handle<v8::Value> JSSystemStruct::proxAddedHandlerCallallback(v8::Handle<v8::Function>cb)
{
return associatedContext->proxAddedHandlerCallallback(cb);
}
v8::Handle<v8::Value> JSSystemStruct::proxRemovedHandlerCallallback(v8::Handle<v8::Function>cb)
{
return associatedContext->proxRemovedHandlerCallallback(cb);
}
v8::Handle<v8::Value> JSSystemStruct::killEntity()
{
return associatedContext->killEntity();
}
v8::Handle<v8::Value> JSSystemStruct::restorePresence(PresStructRestoreParams& psrp)
{
if (!Capabilities::givesCap(mCapNum, Capabilities::CREATE_PRESENCE))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to create presences.")));
return associatedContext->restorePresence(psrp);
}
JSSystemStruct::~JSSystemStruct()
{
}
v8::Handle<v8::Value> JSSystemStruct::deserialize(const String& toDeserialize)
{
return associatedContext->deserialize(toDeserialize);
}
v8::Handle<v8::Value> JSSystemStruct::checkHeadless()
{
return associatedContext->checkHeadless();
}
v8::Handle<v8::Value> JSSystemStruct::struct_require(const String& toRequireFrom,bool isJS)
{
//require uses the same capability as import
if (!Capabilities::givesCap(mCapNum, Capabilities::IMPORT))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to require.")));
return associatedContext->struct_require(toRequireFrom,isJS);
}
v8::Handle<v8::Value> JSSystemStruct::struct_import(const String& toImportFrom,bool isJS)
{
if (!Capabilities::givesCap(mCapNum, Capabilities::IMPORT))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to import.")));
return associatedContext->struct_import(toImportFrom,isJS);
}
v8::Handle<v8::Value> JSSystemStruct::struct_canImport()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::IMPORT));
}
v8::Handle<v8::Value> JSSystemStruct::sendMessageNoErrorHandler(JSPresenceStruct* jspres, const String& serialized_message,JSPositionListener* jspl,bool reliable)
{
//checking capability for this presence
if(getContext()->getAssociatedPresenceStruct() != NULL)
{
if (getContext()->getAssociatedPresenceStruct()->getSporef() == jspres->getSporef())
{
if(!Capabilities::givesCap(mCapNum, Capabilities::SEND_MESSAGE));
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to send messages.")));
}
}
return associatedContext->sendMessageNoErrorHandler(jspres,serialized_message,jspl,reliable);
}
v8::Handle<v8::Value> JSSystemStruct::setSandboxMessageCallback(v8::Persistent<v8::Function> callback)
{
return associatedContext->setSandboxMessageCallback(callback);
}
v8::Handle<v8::Value> JSSystemStruct::setPresenceMessageCallback(v8::Persistent<v8::Function> callback)
{
return associatedContext->setPresenceMessageCallback(callback);
}
JSContextStruct* JSSystemStruct::getContext()
{
return associatedContext;
}
v8::Handle<v8::Value> JSSystemStruct::struct_canCreatePres()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::CREATE_PRESENCE));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canCreateEnt()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::CREATE_ENTITY));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canEval()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::EVAL));
}
//creates and returns a new context object. arguments should be described in
//JSObjects/JSSystem.cpp
//new context will have at most as many permissions as parent context.
//note: if presStruct is null, just means use the one that is associated with
//this system's context
v8::Handle<v8::Value> JSSystemStruct::struct_createContext(JSPresenceStruct* jspres,const SpaceObjectReference& canSendTo, Capabilities::CapNum permNum)
{
//prevents scripter from escalating capabilities beyond those that he/she
//already has
stripCapEscalation(permNum,Capabilities::SEND_MESSAGE,jspres,"SEND_MESSAGE");
stripCapEscalation(permNum,Capabilities::RECEIVE_MESSAGE,jspres,"RECEIVE_MESSAGE");
stripCapEscalation(permNum,Capabilities::IMPORT,jspres,"IMPORT");
stripCapEscalation(permNum,Capabilities::CREATE_PRESENCE,jspres,"CREATE_PRESENCE");
stripCapEscalation(permNum,Capabilities::CREATE_ENTITY,jspres,"CREATE_ENTITY");
stripCapEscalation(permNum,Capabilities::EVAL,jspres,"EVAL");
stripCapEscalation(permNum,Capabilities::PROX_CALLBACKS,jspres,"PROX_CALLBACKS");
stripCapEscalation(permNum,Capabilities::PROX_QUERIES,jspres,"PROX_QUERIES");
stripCapEscalation(permNum,Capabilities::CREATE_SANDBOX,jspres,"CREATE_SANDBOX");
stripCapEscalation(permNum,Capabilities::GUI,jspres,"GUI");
stripCapEscalation(permNum,Capabilities::HTTP,jspres,"HTTP");
stripCapEscalation(permNum,Capabilities::MOVEMENT,jspres,"MOVEMENT");
stripCapEscalation(permNum,Capabilities::MESH, jspres,"MESH");
return associatedContext->struct_createContext(jspres,canSendTo,permNum);
}
void JSSystemStruct::stripCapEscalation(Capabilities::CapNum& permNum, Capabilities::Caps capRequesting, JSPresenceStruct* jspres, const String& capRequestingName)
{
if (! associatedContext->jsObjScript->checkCurCtxtHasCapability(jspres,capRequesting))
{
/*means trying to set this capability when don't have it in the base*/
/*sandbox. We should strip it.*/
JSLOG(info,"Trying to exceed capability " + capRequestingName + " when creating sandbox. Stripping this capability");
permNum -= capRequesting;
}
}
v8::Handle<v8::Value> JSSystemStruct::struct_registerOnPresenceConnectedHandler(v8::Persistent<v8::Function> cb_persist)
{
return associatedContext->struct_registerOnPresenceConnectedHandler(cb_persist);
}
v8::Handle<v8::Value> JSSystemStruct::struct_registerOnPresenceDisconnectedHandler(v8::Persistent<v8::Function> cb_persist)
{
return associatedContext->struct_registerOnPresenceDisconnectedHandler(cb_persist);
}
v8::Handle<v8::Value> JSSystemStruct::struct_setScript(const String& script)
{
return associatedContext->struct_setScript(script);
}
v8::Handle<v8::Value> JSSystemStruct::struct_getScript()
{
return associatedContext->struct_getScript();
}
v8::Handle<v8::Value> JSSystemStruct::struct_reset(const std::map<SpaceObjectReference, std::vector<SpaceObjectReference> > & proxResSet)
{
return associatedContext->struct_setReset(proxResSet);
}
v8::Handle<v8::Value> JSSystemStruct::struct_event(v8::Persistent<v8::Function>& cb) {
return associatedContext->struct_event(cb);
}
//create a timer that will fire in dur seconds from now, that will bind the
//this parameter to target and that will fire the callback cb.
v8::Handle<v8::Value> JSSystemStruct::struct_createTimeout(double period, v8::Persistent<v8::Function>& cb)
{
return associatedContext->struct_createTimeout(period,cb);
}
v8::Handle<v8::Value> JSSystemStruct::struct_createTimeout(double period,v8::Persistent<v8::Function>& cb, uint32 contID,double timeRemaining, bool isSuspended, bool isCleared)
{
return associatedContext->struct_createTimeout(period,cb, contID, timeRemaining, isSuspended,isCleared);
}
//if have the capability to create presences, create a new presence with
//mesh newMesh and executes initFunc, which gets executed onConnected.
//if do not have the capability, throws an error.
v8::Handle<v8::Value> JSSystemStruct::struct_createEntity(EntityCreateInfo& eci)
{
if(!Capabilities::givesCap(mCapNum, Capabilities::CREATE_ENTITY));
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to create entities.")));
return associatedContext->struct_createEntity(eci);
}
v8::Handle<v8::Value> JSSystemStruct::struct_canSendMessage()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::SEND_MESSAGE));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canRecvMessage()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::RECEIVE_MESSAGE));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canProxCallback()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::PROX_CALLBACKS));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canProxChangeQuery()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::PROX_QUERIES));
}
v8::Handle<v8::Value> JSSystemStruct::struct_print(const String& msg)
{
associatedContext->jsscript_print(msg);
return v8::Undefined();
}
v8::Handle<v8::Value> JSSystemStruct::struct_sendHome(const String& toSend)
{
return associatedContext->struct_sendHome(toSend);
}
//decodes system object
JSSystemStruct* JSSystemStruct::decodeSystemStruct(v8::Handle<v8::Value> toDecode ,std::string& errorMessage)
{
v8::HandleScope handle_scope; //for garbage collection.
if (! toDecode->IsObject())
{
errorMessage += "Error in decode of JSSystemStruct. Should have received an object to decode.";
return NULL;
}
v8::Handle<v8::Object> toDecodeObject = toDecode->ToObject();
//now check internal field count
if (toDecodeObject->InternalFieldCount() != SYSTEM_TEMPLATE_FIELD_COUNT)
{
errorMessage += "Error in decode of JSSystemStruct. Object given does not have adequate number of internal fields for decode.";
return NULL;
}
//now actually try to decode each.
//decode the jsVisibleStruct field
v8::Local<v8::External> wrapJSRootStructObj;
wrapJSRootStructObj = v8::Local<v8::External>::Cast(toDecodeObject->GetInternalField(SYSTEM_TEMPLATE_SYSTEM_FIELD));
void* ptr = wrapJSRootStructObj->Value();
JSSystemStruct* returner;
returner = static_cast<JSSystemStruct*>(ptr);
if (returner == NULL)
errorMessage += "Error in decode of JSSystemStruct. Internal field of object given cannot be casted to a JSSystemStruct.";
return returner;
}
Capabilities::CapNum JSSystemStruct::getCapNum()
{
return mCapNum;
}
} //end namespace JS
} //end namespace Sirikata
<commit_msg>Accidentally had included semi-colons at end of if lines when checking capabilities for creating presences. Ie, instead of<commit_after>
#include <v8.h>
#include "JSSystemStruct.hpp"
#include "JSContextStruct.hpp"
#include "../JSObjects/JSFields.hpp"
#include "../JSEntityCreateInfo.hpp"
#include "JSPositionListener.hpp"
#include "JSPresenceStruct.hpp"
#include "../JSLogging.hpp"
#include "../JSObjectScript.hpp"
namespace Sirikata{
namespace JS{
JSSystemStruct::JSSystemStruct ( JSContextStruct* jscont, Capabilities::CapNum capNum)
: associatedContext(jscont),
mCapNum(capNum)
{
}
v8::Handle<v8::Value> JSSystemStruct::struct_evalInGlobal(const String& native_contents, ScriptOrigin* sOrigin)
{
if (!Capabilities::givesCap(mCapNum, Capabilities::EVAL))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability tocall eval in global directly.")));
return associatedContext->struct_evalInGlobal(native_contents,sOrigin);
}
v8::Handle<v8::Value> JSSystemStruct::getAssociatedPresence()
{
return associatedContext->getAssociatedPresence();
}
v8::Handle<v8::Value> JSSystemStruct::storageBeginTransaction() {
return associatedContext->storageBeginTransaction();
}
v8::Handle<v8::Value> JSSystemStruct::storageCommit(v8::Handle<v8::Function> cb)
{
return associatedContext->storageCommit(cb);
}
v8::Handle<v8::Value> JSSystemStruct::storageWrite(const OH::Storage::Key& key, const String& toWrite, v8::Handle<v8::Function> cb)
{
return associatedContext->storageWrite(key, toWrite, cb);
}
v8::Handle<v8::Value> JSSystemStruct::httpRequest(Sirikata::Network::Address addr, Transfer::HttpManager::HTTP_METHOD method, String request, v8::Persistent<v8::Function> cb)
{
return associatedContext->httpRequest(addr,method,request,cb);
}
v8::Handle<v8::Value> JSSystemStruct::storageErase(const OH::Storage::Key& key, v8::Handle<v8::Function> cb)
{
return associatedContext->storageErase(key, cb);
}
v8::Handle<v8::Value> JSSystemStruct::storageRead(const OH::Storage::Key& key, v8::Handle<v8::Function> cb)
{
return associatedContext->storageRead(key, cb);
}
v8::Handle<v8::Value> JSSystemStruct::sendSandbox(const String& msgToSend, JSContextStruct* destination)
{
return associatedContext->sendSandbox(msgToSend,destination);
}
v8::Handle<v8::Value> JSSystemStruct::setRestoreScript(const String& key, v8::Handle<v8::Function> cb)
{
return associatedContext->setRestoreScript(key, cb);
}
v8::Handle<v8::Value> JSSystemStruct::emersonCompileString(const String& toCompile)
{
return associatedContext->emersonCompileString(toCompile);
}
v8::Handle<v8::Value> JSSystemStruct::checkResources()
{
return v8::Boolean::New(true);
}
v8::Handle<v8::Value> JSSystemStruct::debug_fileWrite(const String& strToWrite,const String& filename)
{
return associatedContext->debug_fileWrite(strToWrite,filename);
}
v8::Handle<v8::Value> JSSystemStruct::debug_fileRead(const String& filename)
{
return associatedContext->debug_fileRead(filename);
}
v8::Handle<v8::Value> JSSystemStruct::proxAddedHandlerCallallback(v8::Handle<v8::Function>cb)
{
return associatedContext->proxAddedHandlerCallallback(cb);
}
v8::Handle<v8::Value> JSSystemStruct::proxRemovedHandlerCallallback(v8::Handle<v8::Function>cb)
{
return associatedContext->proxRemovedHandlerCallallback(cb);
}
v8::Handle<v8::Value> JSSystemStruct::killEntity()
{
return associatedContext->killEntity();
}
v8::Handle<v8::Value> JSSystemStruct::restorePresence(PresStructRestoreParams& psrp)
{
if (!Capabilities::givesCap(mCapNum, Capabilities::CREATE_PRESENCE))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to create presences.")));
return associatedContext->restorePresence(psrp);
}
JSSystemStruct::~JSSystemStruct()
{
}
v8::Handle<v8::Value> JSSystemStruct::deserialize(const String& toDeserialize)
{
return associatedContext->deserialize(toDeserialize);
}
v8::Handle<v8::Value> JSSystemStruct::checkHeadless()
{
return associatedContext->checkHeadless();
}
v8::Handle<v8::Value> JSSystemStruct::struct_require(const String& toRequireFrom,bool isJS)
{
//require uses the same capability as import
if (!Capabilities::givesCap(mCapNum, Capabilities::IMPORT))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to require.")));
return associatedContext->struct_require(toRequireFrom,isJS);
}
v8::Handle<v8::Value> JSSystemStruct::struct_import(const String& toImportFrom,bool isJS)
{
if (!Capabilities::givesCap(mCapNum, Capabilities::IMPORT))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to import.")));
return associatedContext->struct_import(toImportFrom,isJS);
}
v8::Handle<v8::Value> JSSystemStruct::struct_canImport()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::IMPORT));
}
v8::Handle<v8::Value> JSSystemStruct::sendMessageNoErrorHandler(JSPresenceStruct* jspres, const String& serialized_message,JSPositionListener* jspl,bool reliable)
{
//checking capability for this presence
if(getContext()->getAssociatedPresenceStruct() != NULL)
{
if (getContext()->getAssociatedPresenceStruct()->getSporef() == jspres->getSporef())
{
if(!Capabilities::givesCap(mCapNum, Capabilities::SEND_MESSAGE))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to send messages.")));
}
}
return associatedContext->sendMessageNoErrorHandler(jspres,serialized_message,jspl,reliable);
}
v8::Handle<v8::Value> JSSystemStruct::setSandboxMessageCallback(v8::Persistent<v8::Function> callback)
{
return associatedContext->setSandboxMessageCallback(callback);
}
v8::Handle<v8::Value> JSSystemStruct::setPresenceMessageCallback(v8::Persistent<v8::Function> callback)
{
return associatedContext->setPresenceMessageCallback(callback);
}
JSContextStruct* JSSystemStruct::getContext()
{
return associatedContext;
}
v8::Handle<v8::Value> JSSystemStruct::struct_canCreatePres()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::CREATE_PRESENCE));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canCreateEnt()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::CREATE_ENTITY));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canEval()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::EVAL));
}
//creates and returns a new context object. arguments should be described in
//JSObjects/JSSystem.cpp
//new context will have at most as many permissions as parent context.
//note: if presStruct is null, just means use the one that is associated with
//this system's context
v8::Handle<v8::Value> JSSystemStruct::struct_createContext(JSPresenceStruct* jspres,const SpaceObjectReference& canSendTo, Capabilities::CapNum permNum)
{
//prevents scripter from escalating capabilities beyond those that he/she
//already has
stripCapEscalation(permNum,Capabilities::SEND_MESSAGE,jspres,"SEND_MESSAGE");
stripCapEscalation(permNum,Capabilities::RECEIVE_MESSAGE,jspres,"RECEIVE_MESSAGE");
stripCapEscalation(permNum,Capabilities::IMPORT,jspres,"IMPORT");
stripCapEscalation(permNum,Capabilities::CREATE_PRESENCE,jspres,"CREATE_PRESENCE");
stripCapEscalation(permNum,Capabilities::CREATE_ENTITY,jspres,"CREATE_ENTITY");
stripCapEscalation(permNum,Capabilities::EVAL,jspres,"EVAL");
stripCapEscalation(permNum,Capabilities::PROX_CALLBACKS,jspres,"PROX_CALLBACKS");
stripCapEscalation(permNum,Capabilities::PROX_QUERIES,jspres,"PROX_QUERIES");
stripCapEscalation(permNum,Capabilities::CREATE_SANDBOX,jspres,"CREATE_SANDBOX");
stripCapEscalation(permNum,Capabilities::GUI,jspres,"GUI");
stripCapEscalation(permNum,Capabilities::HTTP,jspres,"HTTP");
stripCapEscalation(permNum,Capabilities::MOVEMENT,jspres,"MOVEMENT");
stripCapEscalation(permNum,Capabilities::MESH, jspres,"MESH");
return associatedContext->struct_createContext(jspres,canSendTo,permNum);
}
void JSSystemStruct::stripCapEscalation(Capabilities::CapNum& permNum, Capabilities::Caps capRequesting, JSPresenceStruct* jspres, const String& capRequestingName)
{
if (! associatedContext->jsObjScript->checkCurCtxtHasCapability(jspres,capRequesting))
{
/*means trying to set this capability when don't have it in the base*/
/*sandbox. We should strip it.*/
JSLOG(info,"Trying to exceed capability " + capRequestingName + " when creating sandbox. Stripping this capability");
permNum -= capRequesting;
}
}
v8::Handle<v8::Value> JSSystemStruct::struct_registerOnPresenceConnectedHandler(v8::Persistent<v8::Function> cb_persist)
{
return associatedContext->struct_registerOnPresenceConnectedHandler(cb_persist);
}
v8::Handle<v8::Value> JSSystemStruct::struct_registerOnPresenceDisconnectedHandler(v8::Persistent<v8::Function> cb_persist)
{
return associatedContext->struct_registerOnPresenceDisconnectedHandler(cb_persist);
}
v8::Handle<v8::Value> JSSystemStruct::struct_setScript(const String& script)
{
return associatedContext->struct_setScript(script);
}
v8::Handle<v8::Value> JSSystemStruct::struct_getScript()
{
return associatedContext->struct_getScript();
}
v8::Handle<v8::Value> JSSystemStruct::struct_reset(const std::map<SpaceObjectReference, std::vector<SpaceObjectReference> > & proxResSet)
{
return associatedContext->struct_setReset(proxResSet);
}
v8::Handle<v8::Value> JSSystemStruct::struct_event(v8::Persistent<v8::Function>& cb) {
return associatedContext->struct_event(cb);
}
//create a timer that will fire in dur seconds from now, that will bind the
//this parameter to target and that will fire the callback cb.
v8::Handle<v8::Value> JSSystemStruct::struct_createTimeout(double period, v8::Persistent<v8::Function>& cb)
{
return associatedContext->struct_createTimeout(period,cb);
}
v8::Handle<v8::Value> JSSystemStruct::struct_createTimeout(double period,v8::Persistent<v8::Function>& cb, uint32 contID,double timeRemaining, bool isSuspended, bool isCleared)
{
return associatedContext->struct_createTimeout(period,cb, contID, timeRemaining, isSuspended,isCleared);
}
//if have the capability to create presences, create a new presence with
//mesh newMesh and executes initFunc, which gets executed onConnected.
//if do not have the capability, throws an error.
v8::Handle<v8::Value> JSSystemStruct::struct_createEntity(EntityCreateInfo& eci)
{
if(!Capabilities::givesCap(mCapNum, Capabilities::CREATE_ENTITY))
return v8::ThrowException( v8::Exception::Error(v8::String::New("Error. You do not have the capability to create entities.")));
return associatedContext->struct_createEntity(eci);
}
v8::Handle<v8::Value> JSSystemStruct::struct_canSendMessage()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::SEND_MESSAGE));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canRecvMessage()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::RECEIVE_MESSAGE));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canProxCallback()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::PROX_CALLBACKS));
}
v8::Handle<v8::Value> JSSystemStruct::struct_canProxChangeQuery()
{
return v8::Boolean::New(Capabilities::givesCap(mCapNum, Capabilities::PROX_QUERIES));
}
v8::Handle<v8::Value> JSSystemStruct::struct_print(const String& msg)
{
associatedContext->jsscript_print(msg);
return v8::Undefined();
}
v8::Handle<v8::Value> JSSystemStruct::struct_sendHome(const String& toSend)
{
return associatedContext->struct_sendHome(toSend);
}
//decodes system object
JSSystemStruct* JSSystemStruct::decodeSystemStruct(v8::Handle<v8::Value> toDecode ,std::string& errorMessage)
{
v8::HandleScope handle_scope; //for garbage collection.
if (! toDecode->IsObject())
{
errorMessage += "Error in decode of JSSystemStruct. Should have received an object to decode.";
return NULL;
}
v8::Handle<v8::Object> toDecodeObject = toDecode->ToObject();
//now check internal field count
if (toDecodeObject->InternalFieldCount() != SYSTEM_TEMPLATE_FIELD_COUNT)
{
errorMessage += "Error in decode of JSSystemStruct. Object given does not have adequate number of internal fields for decode.";
return NULL;
}
//now actually try to decode each.
//decode the jsVisibleStruct field
v8::Local<v8::External> wrapJSRootStructObj;
wrapJSRootStructObj = v8::Local<v8::External>::Cast(toDecodeObject->GetInternalField(SYSTEM_TEMPLATE_SYSTEM_FIELD));
void* ptr = wrapJSRootStructObj->Value();
JSSystemStruct* returner;
returner = static_cast<JSSystemStruct*>(ptr);
if (returner == NULL)
errorMessage += "Error in decode of JSSystemStruct. Internal field of object given cannot be casted to a JSSystemStruct.";
return returner;
}
Capabilities::CapNum JSSystemStruct::getCapNum()
{
return mCapNum;
}
} //end namespace JS
} //end namespace Sirikata
<|endoftext|> |
<commit_before>/*
* AUTOGENERATED CODE, DO NOT EDIT
*
*
* Copyright (C) 2012 Aldebaran Robotics
*/
#pragma once
#ifndef _QIMESSAGING_DETAILS_BOOSTFUNCTOR_HXX_
#define _QIMESSAGING_DETAILS_BOOSTFUNCTOR_HXX_
#include <boost/mpl/at.hpp>
# include <qimessaging/functor.hpp>
# include <boost/function_types/function_arity.hpp>
# include <boost/function_types/function_type.hpp>
# include <boost/function_types/result_type.hpp>
# include <boost/function_types/parameter_types.hpp>
namespace qi {
namespace detail {
template<int count> struct Invoker {};
template<typename T, typename R, int I> R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms);
// I'm guessing this iteration could be avoided with fusion.
template<> struct Invoker<0> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
return f();
}
};
template<> struct Invoker<1> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
dsi >> p0;
return f(p0);
}
};
template<> struct Invoker<2> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
dsi >> p0;
dsi >> p1;
return f(p0, p1);
}
};
template<> struct Invoker<3> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
dsi >> p0;
dsi >> p1;
dsi >> p2;
return f(p0, p1, p2);
}
};
template<> struct Invoker<4> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
return f(p0, p1, p2, p3);
}
};
template<> struct Invoker<5> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
return f(p0, p1, p2, p3, p4);
}
};
template<> struct Invoker<6> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
return f(p0, p1, p2, p3, p4, p5);
}
};
template<> struct Invoker<7> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
typename boost::mpl::at<ArgsType, boost::mpl::int_<6> >::type p6;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
dsi >> p6;
return f(p0, p1, p2, p3, p4, p5, p6);
}
};
template<> struct Invoker<8> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
typename boost::mpl::at<ArgsType, boost::mpl::int_<6> >::type p6;
typename boost::mpl::at<ArgsType, boost::mpl::int_<7> >::type p7;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
dsi >> p6;
dsi >> p7;
return f(p0, p1, p2, p3, p4, p5, p6, p7);
}
};
template<> struct Invoker<9> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
typename boost::mpl::at<ArgsType, boost::mpl::int_<6> >::type p6;
typename boost::mpl::at<ArgsType, boost::mpl::int_<7> >::type p7;
typename boost::mpl::at<ArgsType, boost::mpl::int_<8> >::type p8;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
dsi >> p6;
dsi >> p7;
dsi >> p8;
return f(p0, p1, p2, p3, p4, p5, p6, p7, p8);
}
};
template<typename T>
class BoostFunctor: public Functor
{
public:
BoostFunctor(boost::function<T> f)
: f(f) {}
void call(const qi::FunctorParameters ¶ms, qi::FunctorResult result) const
{
typedef typename boost::function_types::result_type<T>::type ResultType;
Invoker<boost::function_types::function_arity<T>::value> invoker;
ResultType res = invoker.invoke<T, ResultType>(
const_cast<boost::function<T>&>(f), params);
qi::Buffer buf;
qi::ODataStream dso(buf);
dso << res;
if (sanityCheckAndReport(dso, result))
result.setValue(buf);
}
boost::function<T> f;
};
}
}
#endif // _QIMESSAGING_DETAILS_FUNCTOR_HXX_
<commit_msg>boostfunctor: missing template keyword<commit_after>/*
* AUTOGENERATED CODE, DO NOT EDIT
*
*
* Copyright (C) 2012 Aldebaran Robotics
*/
#pragma once
#ifndef _QIMESSAGING_DETAILS_BOOSTFUNCTOR_HXX_
#define _QIMESSAGING_DETAILS_BOOSTFUNCTOR_HXX_
#include <boost/mpl/at.hpp>
# include <qimessaging/functor.hpp>
# include <boost/function_types/function_arity.hpp>
# include <boost/function_types/function_type.hpp>
# include <boost/function_types/result_type.hpp>
# include <boost/function_types/parameter_types.hpp>
namespace qi {
namespace detail {
template<int count> struct Invoker {};
template<typename T, typename R, int I> R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms);
// I'm guessing this iteration could be avoided with fusion.
template<> struct Invoker<0> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
return f();
}
};
template<> struct Invoker<1> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
dsi >> p0;
return f(p0);
}
};
template<> struct Invoker<2> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
dsi >> p0;
dsi >> p1;
return f(p0, p1);
}
};
template<> struct Invoker<3> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
dsi >> p0;
dsi >> p1;
dsi >> p2;
return f(p0, p1, p2);
}
};
template<> struct Invoker<4> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
return f(p0, p1, p2, p3);
}
};
template<> struct Invoker<5> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
return f(p0, p1, p2, p3, p4);
}
};
template<> struct Invoker<6> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
return f(p0, p1, p2, p3, p4, p5);
}
};
template<> struct Invoker<7> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
typename boost::mpl::at<ArgsType, boost::mpl::int_<6> >::type p6;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
dsi >> p6;
return f(p0, p1, p2, p3, p4, p5, p6);
}
};
template<> struct Invoker<8> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
typename boost::mpl::at<ArgsType, boost::mpl::int_<6> >::type p6;
typename boost::mpl::at<ArgsType, boost::mpl::int_<7> >::type p7;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
dsi >> p6;
dsi >> p7;
return f(p0, p1, p2, p3, p4, p5, p6, p7);
}
};
template<> struct Invoker<9> {
template<typename T, typename R> static
R invoke(boost::function<T>& f, const qi::FunctorParameters ¶ms)
{
typedef typename boost::function_types::parameter_types<T>::type ArgsType;
qi::IDataStream dsi(params.buffer());
typename boost::mpl::at<ArgsType, boost::mpl::int_<0> >::type p0;
typename boost::mpl::at<ArgsType, boost::mpl::int_<1> >::type p1;
typename boost::mpl::at<ArgsType, boost::mpl::int_<2> >::type p2;
typename boost::mpl::at<ArgsType, boost::mpl::int_<3> >::type p3;
typename boost::mpl::at<ArgsType, boost::mpl::int_<4> >::type p4;
typename boost::mpl::at<ArgsType, boost::mpl::int_<5> >::type p5;
typename boost::mpl::at<ArgsType, boost::mpl::int_<6> >::type p6;
typename boost::mpl::at<ArgsType, boost::mpl::int_<7> >::type p7;
typename boost::mpl::at<ArgsType, boost::mpl::int_<8> >::type p8;
dsi >> p0;
dsi >> p1;
dsi >> p2;
dsi >> p3;
dsi >> p4;
dsi >> p5;
dsi >> p6;
dsi >> p7;
dsi >> p8;
return f(p0, p1, p2, p3, p4, p5, p6, p7, p8);
}
};
template<typename T>
class BoostFunctor: public Functor
{
public:
BoostFunctor(boost::function<T> f)
: f(f) {}
void call(const qi::FunctorParameters ¶ms, qi::FunctorResult result) const
{
typedef typename boost::function_types::result_type<T>::type ResultType;
Invoker<boost::function_types::function_arity<T>::value> invoker;
ResultType res = invoker.template invoke<T, ResultType>(
const_cast<boost::function<T>&>(f), params);
qi::Buffer buf;
qi::ODataStream dso(buf);
dso << res;
if (sanityCheckAndReport(dso, result))
result.setValue(buf);
}
boost::function<T> f;
};
}
}
#endif // _QIMESSAGING_DETAILS_FUNCTOR_HXX_
<|endoftext|> |
<commit_before>#ifndef VAST_CONCEPT_PRINTABLE_NUMERIC_INTEGRAL_HPP
#define VAST_CONCEPT_PRINTABLE_NUMERIC_INTEGRAL_HPP
#include <cstdint>
#include <type_traits>
#include "vast/concept/printable/detail/print_numeric.hpp"
#include "vast/concept/printable/core/printer.hpp"
namespace vast {
template <typename T>
struct integral_printer : printer<integral_printer<T>> {
static_assert(std::is_integral<T>{}, "T must be an integral type");
using attribute = T;
template <typename Iterator, typename U = T>
static auto dispatch(Iterator& out, T x)
-> std::enable_if_t<std::is_unsigned<U>{}, bool> {
return detail::print_numeric(out, x);
}
template <typename Iterator, typename U = T>
static auto dispatch(Iterator& out, T x)
-> std::enable_if_t<std::is_signed<U>{}, bool> {
if (x < 0) {
*out++ = '-';
return detail::print_numeric(out, -x);
}
*out++ = '+';
return detail::print_numeric(out, x);
}
template <typename Iterator>
bool print(Iterator& out, T x) const {
return dispatch(out, x);
}
};
template <typename T>
struct printer_registry<T, std::enable_if_t<std::is_integral<T>::value>> {
using type = integral_printer<T>;
};
namespace printers {
// GCC 7.1 complains about this version
//
// template <typename T>
// auto const integral = integral_printer<T>{};
//
// but for some reason doesn't care if we "rewrite" it as follows. (#132)
template <typename T>
const integral_printer<T> integral;
auto const i8 = integral_printer<int8_t>{};
auto const i16 = integral_printer<int16_t>{};
auto const i32 = integral_printer<int32_t>{};
auto const i64 = integral_printer<int64_t>{};
auto const u8 = integral_printer<uint8_t>{};
auto const u16 = integral_printer<uint16_t>{};
auto const u32 = integral_printer<uint32_t>{};
auto const u64 = integral_printer<uint64_t>{};
} // namespace printers
} // namespace vast
#endif
<commit_msg>Attempt to fix dubious compilation issue<commit_after>#ifndef VAST_CONCEPT_PRINTABLE_NUMERIC_INTEGRAL_HPP
#define VAST_CONCEPT_PRINTABLE_NUMERIC_INTEGRAL_HPP
#include <cstdint>
#include <type_traits>
#include "vast/concept/printable/detail/print_numeric.hpp"
#include "vast/concept/printable/core/printer.hpp"
namespace vast {
template <typename T>
struct integral_printer : printer<integral_printer<T>> {
static_assert(std::is_integral<T>{}, "T must be an integral type");
using attribute = T;
template <typename Iterator, typename U = T>
static auto dispatch(Iterator& out, T x)
-> std::enable_if_t<std::is_unsigned<U>{}, bool> {
return detail::print_numeric(out, x);
}
template <typename Iterator, typename U = T>
static auto dispatch(Iterator& out, T x)
-> std::enable_if_t<std::is_signed<U>{}, bool> {
if (x < 0) {
*out++ = '-';
return detail::print_numeric(out, -x);
}
*out++ = '+';
return detail::print_numeric(out, x);
}
template <typename Iterator>
bool print(Iterator& out, T x) const {
return dispatch(out, x);
}
};
template <typename T>
struct printer_registry<T, std::enable_if_t<std::is_integral<T>::value>> {
using type = integral_printer<T>;
};
namespace printers {
// GCC 7.1 complains about this version
//
// template <typename T>
// auto const integral = integral_printer<T>{};
//
// but for some reason doesn't care if we "rewrite" it as follows. (#132)
template <typename T>
const integral_printer<T> integral = integral_printer<T>{};
auto const i8 = integral_printer<int8_t>{};
auto const i16 = integral_printer<int16_t>{};
auto const i32 = integral_printer<int32_t>{};
auto const i64 = integral_printer<int64_t>{};
auto const u8 = integral_printer<uint8_t>{};
auto const u16 = integral_printer<uint16_t>{};
auto const u32 = integral_printer<uint32_t>{};
auto const u64 = integral_printer<uint64_t>{};
} // namespace printers
} // namespace vast
#endif
<|endoftext|> |
<commit_before>/*------------------------------------------------------------------------------
Copyright (c) 2004 Media Development Loan Fund
This file is part of the LiveSupport project.
http://livesupport.campware.org/
To report bugs, send an e-mail to bugs@campware.org
LiveSupport is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
LiveSupport is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with LiveSupport; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
Author : $Author: fgerlits $
Version : $Revision: 1.3 $
Location : $Source: /home/paul/cvs2svn-livesupport/newcvsrepo/livesupport/products/gLiveSupport/src/CuePlayer.cxx,v $
------------------------------------------------------------------------------*/
/* ============================================================ include files */
#ifdef HAVE_CONFIG_H
#include "configure.h"
#endif
#include <iostream>
#include "LiveSupport/Widgets/WidgetFactory.h"
#include "CuePlayer.h"
using namespace LiveSupport::Core;
using namespace LiveSupport::Widgets;
using namespace LiveSupport::GLiveSupport;
/* =================================================== local data structures */
/* ================================================ local constants & macros */
/* =============================================== local function prototypes */
/* ============================================================= module code */
/*------------------------------------------------------------------------------
* Constructor.
*----------------------------------------------------------------------------*/
CuePlayer :: CuePlayer(Ptr<GLiveSupport>::Ref gLiveSupport,
Gtk::TreeView * treeView,
const PlayableTreeModelColumnRecord & modelColumns)
throw ()
: gLiveSupport(gLiveSupport),
treeView(treeView),
modelColumns(modelColumns)
{
Ptr<WidgetFactory>::Ref wf = WidgetFactory::getInstance();
playButton = Gtk::manage(wf->createButton(
WidgetFactory::smallPlayButton ));
pauseButton = Gtk::manage(wf->createButton(
WidgetFactory::smallPauseButton ));
stopButton = Gtk::manage(wf->createButton(
WidgetFactory::smallStopButton ));
playButton->signal_clicked().connect(sigc::mem_fun(*this,
&CuePlayer::onPlayButtonClicked ));
pauseButton->signal_clicked().connect(sigc::mem_fun(*this,
&CuePlayer::onPauseButtonClicked ));
stopButton->signal_clicked().connect(sigc::mem_fun(*this,
&CuePlayer::onStopButtonClicked ));
pack_end(*stopButton, Gtk::PACK_SHRINK, 3);
pack_end(*playButton, Gtk::PACK_SHRINK, 3);
audioState = waitingState;
gLiveSupport->attachCueAudioListener(this);
}
/*------------------------------------------------------------------------------
* Destructor.
*----------------------------------------------------------------------------*/
CuePlayer :: ~CuePlayer(void) throw ()
{
try {
gLiveSupport->detachCueAudioListener(this);
} catch (std::invalid_argument &e) {
std::cerr << "Could not detach cue player audio listener."
<< std::endl;
}
}
/*------------------------------------------------------------------------------
* Event handler for the Play menu item selected from the entry conext menu
*----------------------------------------------------------------------------*/
void
CuePlayer :: onPlayItem(void) throw ()
{
Glib::RefPtr<Gtk::TreeView::Selection> refSelection =
treeView->get_selection();
if (refSelection) {
Gtk::TreeModel::iterator iter = refSelection->get_selected();
if (iter) {
Ptr<Playable>::Ref playable = (*iter)[modelColumns.playableColumn];
try {
gLiveSupport->playCueAudio(playable);
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::playCueAudio() error:"
<< std::endl << e.what() << std::endl;
}
audioState = playingState;
remove(*playButton);
pack_end(*pauseButton, Gtk::PACK_SHRINK, 3);
pauseButton->show();
}
}
}
/*------------------------------------------------------------------------------
* Event handler for the Play button getting clicked
*----------------------------------------------------------------------------*/
void
CuePlayer :: onPlayButtonClicked(void) throw ()
{
switch (audioState) {
case waitingState:
onPlayItem();
break;
case pausedState:
try {
gLiveSupport->pauseCueAudio(); // ie, restart
audioState = playingState;
remove(*playButton);
pack_end(*pauseButton, Gtk::PACK_SHRINK, 3);
pauseButton->show();
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::pauseCueAudio() error:" << std::endl
<< e.what() << std::endl;
}
break;
case playingState: // should never happen
std::cerr << "Assertion failed in CuePlayer:" << std::endl
<< "play button clicked when it should not be visible."
<< std::endl;
break;
}
}
/*------------------------------------------------------------------------------
* Event handler for the Pause button getting clicked
*----------------------------------------------------------------------------*/
void
CuePlayer :: onPauseButtonClicked(void) throw ()
{
try {
gLiveSupport->pauseCueAudio();
audioState = pausedState;
remove(*pauseButton);
pack_end(*playButton, Gtk::PACK_SHRINK, 3);
playButton->show();
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::pauseCueAudio() error:" << std::endl
<< e.what() << std::endl;
}
}
/*------------------------------------------------------------------------------
* Event handler for the Stop button getting clicked
*----------------------------------------------------------------------------*/
void
CuePlayer :: onStopButtonClicked(void) throw ()
{
if (audioState != waitingState) {
try {
gLiveSupport->stopCueAudio();
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::stopCueAudio() error:" << std::endl
<< e.what() << std::endl;
}
}
}
/*------------------------------------------------------------------------------
* Event handler for the "cue audio player has stopped" event.
*----------------------------------------------------------------------------*/
void
CuePlayer :: onStop(void) throw ()
{
switch (audioState) {
case pausedState:
remove(*playButton);
break;
case playingState:
remove(*pauseButton);
break;
case waitingState: // sometimes onStop() is called twice
return;
}
audioState = waitingState;
pack_end(*playButton, Gtk::PACK_SHRINK, 3);
playButton->show();
}
<commit_msg>fixed CuePlayer to support multiple selections<commit_after>/*------------------------------------------------------------------------------
Copyright (c) 2004 Media Development Loan Fund
This file is part of the LiveSupport project.
http://livesupport.campware.org/
To report bugs, send an e-mail to bugs@campware.org
LiveSupport is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
LiveSupport is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with LiveSupport; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
Author : $Author: fgerlits $
Version : $Revision: 1.4 $
Location : $Source: /home/paul/cvs2svn-livesupport/newcvsrepo/livesupport/products/gLiveSupport/src/CuePlayer.cxx,v $
------------------------------------------------------------------------------*/
/* ============================================================ include files */
#ifdef HAVE_CONFIG_H
#include "configure.h"
#endif
#include <iostream>
#include "LiveSupport/Widgets/WidgetFactory.h"
#include "CuePlayer.h"
using namespace LiveSupport::Core;
using namespace LiveSupport::Widgets;
using namespace LiveSupport::GLiveSupport;
/* =================================================== local data structures */
/* ================================================ local constants & macros */
/* =============================================== local function prototypes */
/* ============================================================= module code */
/*------------------------------------------------------------------------------
* Constructor.
*----------------------------------------------------------------------------*/
CuePlayer :: CuePlayer(Ptr<GLiveSupport>::Ref gLiveSupport,
Gtk::TreeView * treeView,
const PlayableTreeModelColumnRecord & modelColumns)
throw ()
: gLiveSupport(gLiveSupport),
treeView(treeView),
modelColumns(modelColumns)
{
Ptr<WidgetFactory>::Ref wf = WidgetFactory::getInstance();
playButton = Gtk::manage(wf->createButton(
WidgetFactory::smallPlayButton ));
pauseButton = Gtk::manage(wf->createButton(
WidgetFactory::smallPauseButton ));
stopButton = Gtk::manage(wf->createButton(
WidgetFactory::smallStopButton ));
playButton->signal_clicked().connect(sigc::mem_fun(*this,
&CuePlayer::onPlayButtonClicked ));
pauseButton->signal_clicked().connect(sigc::mem_fun(*this,
&CuePlayer::onPauseButtonClicked ));
stopButton->signal_clicked().connect(sigc::mem_fun(*this,
&CuePlayer::onStopButtonClicked ));
pack_end(*stopButton, Gtk::PACK_SHRINK, 3);
pack_end(*playButton, Gtk::PACK_SHRINK, 3);
audioState = waitingState;
gLiveSupport->attachCueAudioListener(this);
}
/*------------------------------------------------------------------------------
* Destructor.
*----------------------------------------------------------------------------*/
CuePlayer :: ~CuePlayer(void) throw ()
{
try {
gLiveSupport->detachCueAudioListener(this);
} catch (std::invalid_argument &e) {
std::cerr << "Could not detach cue player audio listener."
<< std::endl;
}
}
/*------------------------------------------------------------------------------
* Event handler for the Play menu item selected from the entry conext menu
*----------------------------------------------------------------------------*/
void
CuePlayer :: onPlayItem(void) throw ()
{
Glib::RefPtr<Gtk::TreeView::Selection>
selection = treeView->get_selection();
std::vector<Gtk::TreePath>
selectedRows = selection->get_selected_rows();
if (selectedRows.size() == 1) {
Gtk::TreePath path = selectedRows.front();
Gtk::TreeIter iter = treeView->get_model()->get_iter(path);
if (iter) {
Ptr<Playable>::Ref playable = (*iter)[modelColumns.playableColumn];
try {
gLiveSupport->playCueAudio(playable);
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::playCueAudio() error:"
<< std::endl << e.what() << std::endl;
}
audioState = playingState;
remove(*playButton);
pack_end(*pauseButton, Gtk::PACK_SHRINK, 3);
pauseButton->show();
}
}
}
/*------------------------------------------------------------------------------
* Event handler for the Play button getting clicked
*----------------------------------------------------------------------------*/
void
CuePlayer :: onPlayButtonClicked(void) throw ()
{
switch (audioState) {
case waitingState:
onPlayItem();
break;
case pausedState:
try {
gLiveSupport->pauseCueAudio(); // ie, restart
audioState = playingState;
remove(*playButton);
pack_end(*pauseButton, Gtk::PACK_SHRINK, 3);
pauseButton->show();
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::pauseCueAudio() error:" << std::endl
<< e.what() << std::endl;
}
break;
case playingState: // should never happen
std::cerr << "Assertion failed in CuePlayer:" << std::endl
<< "play button clicked when it should not be visible."
<< std::endl;
break;
}
}
/*------------------------------------------------------------------------------
* Event handler for the Pause button getting clicked
*----------------------------------------------------------------------------*/
void
CuePlayer :: onPauseButtonClicked(void) throw ()
{
try {
gLiveSupport->pauseCueAudio();
audioState = pausedState;
remove(*pauseButton);
pack_end(*playButton, Gtk::PACK_SHRINK, 3);
playButton->show();
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::pauseCueAudio() error:" << std::endl
<< e.what() << std::endl;
}
}
/*------------------------------------------------------------------------------
* Event handler for the Stop button getting clicked
*----------------------------------------------------------------------------*/
void
CuePlayer :: onStopButtonClicked(void) throw ()
{
if (audioState != waitingState) {
try {
gLiveSupport->stopCueAudio();
} catch (std::logic_error &e) {
std::cerr << "GLiveSupport::stopCueAudio() error:" << std::endl
<< e.what() << std::endl;
}
}
}
/*------------------------------------------------------------------------------
* Event handler for the "cue audio player has stopped" event.
*----------------------------------------------------------------------------*/
void
CuePlayer :: onStop(void) throw ()
{
switch (audioState) {
case pausedState:
remove(*playButton);
break;
case playingState:
remove(*pauseButton);
break;
case waitingState: // sometimes onStop() is called twice
return;
}
audioState = waitingState;
pack_end(*playButton, Gtk::PACK_SHRINK, 3);
playButton->show();
}
<|endoftext|> |
<commit_before>#include "Thread/Unix/ThreadImpl.hh"
#include "Thread/ThreadException.hh"
namespace LilWrapper
{
ThreadImpl::ThreadImpl(Thread *thread)
{
this->_isActive = pthread_create(&this->_thread, NULL,
&ThreadImpl::entryPoint, thread) == 0;
if (!this->_isActive)
throw ThreadException("Thread Exception: "
"Error while creating the Thread.");
}
ThreadImpl::~ThreadImpl()
{
if (this->_isActive)
terminate();
}
void ThreadImpl::wait()
{
if (this->_isActive)
{
if (pthread_equal(pthread_self(), this->_thread) != 0)
throw ThreadException("Thread Exception: "
"A thread cannot wait for itself.");
pthread_join(this->_thread, NULL);
}
}
void ThreadImpl::terminate()
{
if (this->_isActive)
pthread_cancel(this->_thread);
}
void *ThreadImpl::entryPoint(void *data)
{
Thread *self = static_cast<Thread *>(data);
pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL);
self->run();
return (NULL);
}
}
<commit_msg>Set the Thread as inactive when terminating it.<commit_after>#include "Thread/Unix/ThreadImpl.hh"
#include "Thread/ThreadException.hh"
namespace LilWrapper
{
ThreadImpl::ThreadImpl(Thread *thread)
{
this->_isActive = pthread_create(&this->_thread, NULL,
&ThreadImpl::entryPoint, thread) == 0;
if (!this->_isActive)
throw ThreadException("Thread Exception: "
"Error while creating the Thread.");
}
ThreadImpl::~ThreadImpl()
{
if (this->_isActive)
terminate();
}
void ThreadImpl::wait()
{
if (this->_isActive)
{
if (pthread_equal(pthread_self(), this->_thread) != 0)
throw ThreadException("Thread Exception: "
"A thread cannot wait for itself.");
pthread_join(this->_thread, NULL);
}
}
void ThreadImpl::terminate()
{
if (this->_isActive)
pthread_cancel(this->_thread);
this->_isActive = false;
}
void *ThreadImpl::entryPoint(void *data)
{
Thread *self = static_cast<Thread *>(data);
pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL);
self->run();
return (NULL);
}
}
<|endoftext|> |
<commit_before>/* -*- Mode: C++; tab-width: 4; indent-tabs-mode: nil; c-basic-offset: 4 -*- */
/*
* This file is part of the LibreOffice project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* This file incorporates work covered by the following license notice:
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed
* with this work for additional information regarding copyright
* ownership. The ASF licenses this file to you under the Apache
* License, Version 2.0 (the "License"); you may not use this file
* except in compliance with the License. You may obtain a copy of
* the License at http://www.apache.org/licenses/LICENSE-2.0 .
*/
#include "oox/vml/vmlformatting.hxx"
#include "oox/vml/vmltextboxcontext.hxx"
#include "oox/vml/vmlshape.hxx"
#include <com/sun/star/drawing/XShape.hpp>
namespace oox {
namespace vml {
// ============================================================================
using ::oox::core::ContextHandler2;
using ::oox::core::ContextHandler2Helper;
using ::oox::core::ContextHandlerRef;
// ============================================================================
TextPortionContext::TextPortionContext( ContextHandler2Helper& rParent,
TextBox& rTextBox, const TextFontModel& rParentFont,
sal_Int32 nElement, const AttributeList& rAttribs ) :
ContextHandler2( rParent ),
mrTextBox( rTextBox ),
maFont( rParentFont ),
mnInitialPortions( rTextBox.getPortionCount() )
{
switch( nElement )
{
case XML_font:
maFont.moName = rAttribs.getXString( XML_face );
maFont.moColor = rAttribs.getXString( XML_color );
maFont.monSize = rAttribs.getInteger( XML_size );
break;
case XML_u:
OSL_ENSURE( !maFont.monUnderline, "TextPortionContext::TextPortionContext - nested <u> elements" );
maFont.monUnderline = (rAttribs.getToken( XML_class, XML_TOKEN_INVALID ) == XML_font4) ? XML_double : XML_single;
break;
case XML_sub:
case XML_sup:
OSL_ENSURE( !maFont.monEscapement, "TextPortionContext::TextPortionContext - nested <sub> or <sup> elements" );
maFont.monEscapement = nElement;
break;
case XML_b:
OSL_ENSURE( !maFont.mobBold, "TextPortionContext::TextPortionContext - nested <b> elements" );
maFont.mobBold = true;
break;
case XML_i:
OSL_ENSURE( !maFont.mobItalic, "TextPortionContext::TextPortionContext - nested <i> elements" );
maFont.mobItalic = true;
break;
case XML_s:
OSL_ENSURE( !maFont.mobStrikeout, "TextPortionContext::TextPortionContext - nested <s> elements" );
maFont.mobStrikeout = true;
break;
case OOX_TOKEN(dml, blip):
{
OptValue<OUString> oRelId = rAttribs.getString(R_TOKEN(embed));
if (oRelId.has())
mrTextBox.mrTypeModel.moGraphicPath = getFragmentPathFromRelId(oRelId.get());
}
break;
case VML_TOKEN(imagedata):
{
OptValue<OUString> oRelId = rAttribs.getString(R_TOKEN(id));
if (oRelId.has())
mrTextBox.mrTypeModel.moGraphicPath = getFragmentPathFromRelId(oRelId.get());
}
break;
case XML_span:
case OOX_TOKEN(doc, r):
break;
default:
OSL_ENSURE( false, "TextPortionContext::TextPortionContext - unknown element" );
}
}
ContextHandlerRef TextPortionContext::onCreateContext( sal_Int32 nElement, const AttributeList& rAttribs )
{
OSL_ENSURE( nElement != XML_font, "TextPortionContext::onCreateContext - nested <font> elements" );
if (getNamespace(getCurrentElement()) == NMSP_doc)
return this;
return new TextPortionContext( *this, mrTextBox, maFont, nElement, rAttribs );
}
void TextPortionContext::onCharacters( const OUString& rChars )
{
if (getNamespace(getCurrentElement()) == NMSP_doc && getCurrentElement() != OOX_TOKEN(doc, t))
return;
switch( getCurrentElement() )
{
case XML_span:
// replace all NBSP characters with SP
mrTextBox.appendPortion( maFont, rChars.replace( 0xA0, ' ' ) );
break;
default:
mrTextBox.appendPortion( maFont, rChars );
}
}
void TextPortionContext::onStartElement(const AttributeList& rAttribs)
{
switch (getCurrentElement())
{
case OOX_TOKEN(doc, b):
maFont.mobBold = true;
break;
case OOX_TOKEN(doc, sz):
maFont.monSize = rAttribs.getInteger( OOX_TOKEN(doc, val) );
break;
}
}
void TextPortionContext::onEndElement()
{
if (getNamespace(getCurrentElement()) == NMSP_doc && getCurrentElement() != OOX_TOKEN(doc, t))
return;
/* A child element without own child elements may contain a single space
character, for example:
<div>
<font><i>abc</i></font>
<font> </font>
<font><b>def</b></font>
</div>
represents the italic text 'abc', an unformatted space character, and
the bold text 'def'. Unfortunately, the XML parser skips the space
character without issuing a 'characters' event. The class member
'mnInitialPortions' contains the number of text portions existing when
this context has been constructed. If no text has been added in the
meantime, the space character has to be added manually.
*/
if( mrTextBox.getPortionCount() == mnInitialPortions )
mrTextBox.appendPortion( maFont, OUString( sal_Unicode( ' ' ) ) );
}
// ============================================================================
TextBoxContext::TextBoxContext( ContextHandler2Helper& rParent, TextBox& rTextBox, const AttributeList& rAttribs,
const GraphicHelper& graphicHelper ) :
ContextHandler2( rParent ),
mrTextBox( rTextBox )
{
if( rAttribs.getString( XML_insetmode ).get() != "auto" )
{
OUString inset = rAttribs.getString( XML_inset ).get();
OUString value;
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceLeft = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.1in" : value, 0, false, false );
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceTop = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.05in" : value, 0, false, false );
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceRight = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.1in" : value, 0, false, false );
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceBottom = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.05in" : value, 0, false, false );
rTextBox.borderDistanceSet = true;
}
OUString sStyle = rAttribs.getString( XML_style, OUString() );
sal_Int32 nIndex = 0;
while( nIndex >= 0 )
{
OUString aName, aValue;
if( ConversionHelper::separatePair( aName, aValue, sStyle.getToken( 0, ';', nIndex ), ':' ) )
{
if( aName == "layout-flow" ) rTextBox.maLayoutFlow = aValue;
else if (aName == "mso-fit-shape-to-text")
rTextBox.mrTypeModel.mbAutoHeight = true;
else
SAL_WARN("oox", "unhandled style property: " << aName);
}
}
}
ContextHandlerRef TextBoxContext::onCreateContext( sal_Int32 nElement, const AttributeList& rAttribs )
{
switch( getCurrentElement() )
{
case VML_TOKEN( textbox ):
if( nElement == XML_div ) return this;
else if (nElement == OOX_TOKEN(doc, txbxContent)) return this;
break;
case XML_div:
if( nElement == XML_font ) return new TextPortionContext( *this, mrTextBox, TextFontModel(), nElement, rAttribs );
break;
case OOX_TOKEN(doc, txbxContent):
if (nElement == OOX_TOKEN(doc, p)) return this;
break;
case OOX_TOKEN(doc, p):
if (nElement == OOX_TOKEN(doc, r)) return new TextPortionContext( *this, mrTextBox, TextFontModel(), nElement, rAttribs );
break;
}
return 0;
}
// ============================================================================
} // namespace vml
} // namespace oox
/* vim:set shiftwidth=4 softtabstop=4 expandtab: */
<commit_msg>fdo#46361 oox: handle w:br for groupshape textboxes<commit_after>/* -*- Mode: C++; tab-width: 4; indent-tabs-mode: nil; c-basic-offset: 4 -*- */
/*
* This file is part of the LibreOffice project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* This file incorporates work covered by the following license notice:
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed
* with this work for additional information regarding copyright
* ownership. The ASF licenses this file to you under the Apache
* License, Version 2.0 (the "License"); you may not use this file
* except in compliance with the License. You may obtain a copy of
* the License at http://www.apache.org/licenses/LICENSE-2.0 .
*/
#include "oox/vml/vmlformatting.hxx"
#include "oox/vml/vmltextboxcontext.hxx"
#include "oox/vml/vmlshape.hxx"
#include <com/sun/star/drawing/XShape.hpp>
namespace oox {
namespace vml {
// ============================================================================
using ::oox::core::ContextHandler2;
using ::oox::core::ContextHandler2Helper;
using ::oox::core::ContextHandlerRef;
// ============================================================================
TextPortionContext::TextPortionContext( ContextHandler2Helper& rParent,
TextBox& rTextBox, const TextFontModel& rParentFont,
sal_Int32 nElement, const AttributeList& rAttribs ) :
ContextHandler2( rParent ),
mrTextBox( rTextBox ),
maFont( rParentFont ),
mnInitialPortions( rTextBox.getPortionCount() )
{
switch( nElement )
{
case XML_font:
maFont.moName = rAttribs.getXString( XML_face );
maFont.moColor = rAttribs.getXString( XML_color );
maFont.monSize = rAttribs.getInteger( XML_size );
break;
case XML_u:
OSL_ENSURE( !maFont.monUnderline, "TextPortionContext::TextPortionContext - nested <u> elements" );
maFont.monUnderline = (rAttribs.getToken( XML_class, XML_TOKEN_INVALID ) == XML_font4) ? XML_double : XML_single;
break;
case XML_sub:
case XML_sup:
OSL_ENSURE( !maFont.monEscapement, "TextPortionContext::TextPortionContext - nested <sub> or <sup> elements" );
maFont.monEscapement = nElement;
break;
case XML_b:
OSL_ENSURE( !maFont.mobBold, "TextPortionContext::TextPortionContext - nested <b> elements" );
maFont.mobBold = true;
break;
case XML_i:
OSL_ENSURE( !maFont.mobItalic, "TextPortionContext::TextPortionContext - nested <i> elements" );
maFont.mobItalic = true;
break;
case XML_s:
OSL_ENSURE( !maFont.mobStrikeout, "TextPortionContext::TextPortionContext - nested <s> elements" );
maFont.mobStrikeout = true;
break;
case OOX_TOKEN(dml, blip):
{
OptValue<OUString> oRelId = rAttribs.getString(R_TOKEN(embed));
if (oRelId.has())
mrTextBox.mrTypeModel.moGraphicPath = getFragmentPathFromRelId(oRelId.get());
}
break;
case VML_TOKEN(imagedata):
{
OptValue<OUString> oRelId = rAttribs.getString(R_TOKEN(id));
if (oRelId.has())
mrTextBox.mrTypeModel.moGraphicPath = getFragmentPathFromRelId(oRelId.get());
}
break;
case XML_span:
case OOX_TOKEN(doc, r):
break;
default:
OSL_ENSURE( false, "TextPortionContext::TextPortionContext - unknown element" );
}
}
ContextHandlerRef TextPortionContext::onCreateContext( sal_Int32 nElement, const AttributeList& rAttribs )
{
OSL_ENSURE( nElement != XML_font, "TextPortionContext::onCreateContext - nested <font> elements" );
if (getNamespace(getCurrentElement()) == NMSP_doc)
return this;
return new TextPortionContext( *this, mrTextBox, maFont, nElement, rAttribs );
}
void TextPortionContext::onCharacters( const OUString& rChars )
{
if (getNamespace(getCurrentElement()) == NMSP_doc && getCurrentElement() != OOX_TOKEN(doc, t))
return;
switch( getCurrentElement() )
{
case XML_span:
// replace all NBSP characters with SP
mrTextBox.appendPortion( maFont, rChars.replace( 0xA0, ' ' ) );
break;
default:
mrTextBox.appendPortion( maFont, rChars );
}
}
void TextPortionContext::onStartElement(const AttributeList& rAttribs)
{
switch (getCurrentElement())
{
case OOX_TOKEN(doc, b):
maFont.mobBold = true;
break;
case OOX_TOKEN(doc, sz):
maFont.monSize = rAttribs.getInteger( OOX_TOKEN(doc, val) );
break;
case OOX_TOKEN(doc, br):
mrTextBox.appendPortion( maFont, "\n" );
break;
}
}
void TextPortionContext::onEndElement()
{
if (getNamespace(getCurrentElement()) == NMSP_doc && getCurrentElement() != OOX_TOKEN(doc, t))
return;
/* A child element without own child elements may contain a single space
character, for example:
<div>
<font><i>abc</i></font>
<font> </font>
<font><b>def</b></font>
</div>
represents the italic text 'abc', an unformatted space character, and
the bold text 'def'. Unfortunately, the XML parser skips the space
character without issuing a 'characters' event. The class member
'mnInitialPortions' contains the number of text portions existing when
this context has been constructed. If no text has been added in the
meantime, the space character has to be added manually.
*/
if( mrTextBox.getPortionCount() == mnInitialPortions )
mrTextBox.appendPortion( maFont, OUString( sal_Unicode( ' ' ) ) );
}
// ============================================================================
TextBoxContext::TextBoxContext( ContextHandler2Helper& rParent, TextBox& rTextBox, const AttributeList& rAttribs,
const GraphicHelper& graphicHelper ) :
ContextHandler2( rParent ),
mrTextBox( rTextBox )
{
if( rAttribs.getString( XML_insetmode ).get() != "auto" )
{
OUString inset = rAttribs.getString( XML_inset ).get();
OUString value;
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceLeft = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.1in" : value, 0, false, false );
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceTop = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.05in" : value, 0, false, false );
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceRight = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.1in" : value, 0, false, false );
ConversionHelper::separatePair( value, inset, inset, ',' );
rTextBox.borderDistanceBottom = ConversionHelper::decodeMeasureToHmm( graphicHelper,
value.isEmpty() ? "0.05in" : value, 0, false, false );
rTextBox.borderDistanceSet = true;
}
OUString sStyle = rAttribs.getString( XML_style, OUString() );
sal_Int32 nIndex = 0;
while( nIndex >= 0 )
{
OUString aName, aValue;
if( ConversionHelper::separatePair( aName, aValue, sStyle.getToken( 0, ';', nIndex ), ':' ) )
{
if( aName == "layout-flow" ) rTextBox.maLayoutFlow = aValue;
else if (aName == "mso-fit-shape-to-text")
rTextBox.mrTypeModel.mbAutoHeight = true;
else
SAL_WARN("oox", "unhandled style property: " << aName);
}
}
}
ContextHandlerRef TextBoxContext::onCreateContext( sal_Int32 nElement, const AttributeList& rAttribs )
{
switch( getCurrentElement() )
{
case VML_TOKEN( textbox ):
if( nElement == XML_div ) return this;
else if (nElement == OOX_TOKEN(doc, txbxContent)) return this;
break;
case XML_div:
if( nElement == XML_font ) return new TextPortionContext( *this, mrTextBox, TextFontModel(), nElement, rAttribs );
break;
case OOX_TOKEN(doc, txbxContent):
if (nElement == OOX_TOKEN(doc, p)) return this;
break;
case OOX_TOKEN(doc, p):
if (nElement == OOX_TOKEN(doc, r)) return new TextPortionContext( *this, mrTextBox, TextFontModel(), nElement, rAttribs );
break;
}
return 0;
}
// ============================================================================
} // namespace vml
} // namespace oox
/* vim:set shiftwidth=4 softtabstop=4 expandtab: */
<|endoftext|> |
<commit_before>//////////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2004-2020 musikcube team
//
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * 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.
//
// * Neither the name of the author nor the names of other 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 <stdafx.h>
#include "TrackRowRenderers.h"
#include <cursespp/Colors.h>
#include <cursespp/SingleLineEntry.h>
#include <cursespp/Text.h>
#include <musikcore/support/PreferenceKeys.h>
#include <musikcore/library/LocalLibraryConstants.h>
#include <musikcore/support/Duration.h>
#include <app/util/Rating.h>
#include <app/util/PreferenceKeys.h>
#include <math.h>
using namespace musik::core;
using namespace musik::core::library;
using namespace musik::cube;
using namespace musik::cube::TrackRowRenderers;
using namespace cursespp;
#define DIGITS(x) (x > 9 ? (int) log10((double) x) + 1 : 1)
static const int kDurationColWidth = 5; /* 00:00 */
static const int kRatingBreakpointWidth = 90;
/* this method does a couple things slower than it probably should, but it
shouldn't cause any issues. TODO: make this better? does it matter? */
static inline std::string getRatingForTrack(TrackPtr track, size_t width) {
if (width <= kRatingBreakpointWidth) {
return "";
}
auto p = Preferences::ForComponent(musik::core::prefs::components::Settings);
if (p->GetBool(musik::cube::prefs::keys::DisableRatingColumn, false)) {
return "";
}
const int rating = std::max(0, std::min(5, track->GetInt32("rating", 0)));
return " " + getRatingString(rating);
}
static std::string placeholder(int width) {
std::string result;
for (int i = 0; i < width; i++) {
result += "-"; // "░";
}
return result;
}
namespace AlbumSort {
static const int kTrackColWidth = 3;
static const int kArtistColWidth = 17;
static const int kRatingColumnWidth = 5;
static std::string skeleton(TrackPtr track, size_t width) {
auto const id = track->GetId();
std::string rating = width <= kRatingBreakpointWidth ? "" : getRatingString(0);
std::string trackNum = text::Align(placeholder(2), text::AlignRight, kTrackColWidth);
std::string duration = text::Align("0:00", text::AlignRight, kDurationColWidth);
std::string artist = text::Align(placeholder(1 + (id % (kArtistColWidth - 2))), text::AlignLeft, kArtistColWidth);
int titleWidth =
(int) width -
(int) kTrackColWidth -
kDurationColWidth -
kArtistColWidth -
(int) u8len(rating) -
(3 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(placeholder(1 + (id % ((int64_t) titleWidth - 2))), text::AlignLeft, (int) titleWidth);
return u8fmt(
"%s %s%s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
artist.c_str());
}
static const Renderer renderer = [](TrackPtr track, size_t index, size_t width, TrackNumType type) -> std::string {
if (track->GetMetadataState() != musik::core::sdk::MetadataState::Loaded) {
return skeleton(track, width);
}
std::string trackNum;
std::string rating = getRatingForTrack(track, width);
int trackColWidth = kTrackColWidth;
if (type == TrackNumType::Metadata) {
trackNum = text::Align(
track->GetString(constants::Track::TRACK_NUM),
text::AlignRight,
kTrackColWidth);
}
else {
trackColWidth = std::max(kTrackColWidth, DIGITS(index + 1));
trackNum = text::Align(std::to_string(index + 1), text::AlignRight, trackColWidth);
}
std::string duration = text::Align(
musik::core::duration::Duration(track->GetString(constants::Track::DURATION)),
text::AlignRight,
kDurationColWidth);
std::string artist = text::Align(
track->GetString(constants::Track::ARTIST),
text::AlignLeft,
kArtistColWidth);
int titleWidth = 0;
titleWidth =
(int) width -
(int) trackColWidth -
kDurationColWidth -
kArtistColWidth -
(int) u8len(rating) -
(3 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(
track->GetString(constants::Track::TITLE),
text::AlignLeft,
(int) titleWidth);
return u8fmt(
"%s %s%s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
artist.c_str());
};
}
namespace NowPlaying {
static const int kTrackColWidth = 3;
static const int kArtistColWidth = 14;
static const int kAlbumColWidth = 14;
static std::string skeleton(TrackPtr track, size_t width) {
auto const id = track->GetId();
std::string rating = width <= kRatingBreakpointWidth ? "" : getRatingString(0);
std::string trackNum = text::Align(placeholder(2), text::AlignRight, kTrackColWidth);
std::string duration = text::Align("0:00", text::AlignRight, kDurationColWidth);
std::string album = text::Align(placeholder(1 + (id % (kAlbumColWidth - 2))), text::AlignLeft, kAlbumColWidth);
std::string artist = text::Align(placeholder(1 + (id % (kArtistColWidth - 2))), text::AlignLeft, kArtistColWidth);
int titleWidth =
(int)width -
(int)kTrackColWidth -
kDurationColWidth -
kAlbumColWidth -
kArtistColWidth -
(int)u8len(rating) -
(4 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(placeholder(1 + (id % ((int64_t) titleWidth - 2))), text::AlignLeft, (int) titleWidth);
return u8fmt(
"%s %s%s %s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
album.c_str(),
artist.c_str());
}
static const Renderer renderer = [](TrackPtr track, size_t index, size_t width, TrackNumType type) -> std::string {
if (track->GetMetadataState() != musik::core::sdk::MetadataState::Loaded) {
return skeleton(track, width);
}
const size_t trackColWidth = std::max(kTrackColWidth, DIGITS(index + 1));
std::string trackNum = text::Align(std::to_string(index + 1), text::AlignRight, trackColWidth);
std::string rating = getRatingForTrack(track, width);
std::string duration = text::Align(
duration::Duration(track->GetString(constants::Track::DURATION)),
text::AlignRight,
kDurationColWidth);
std::string album = text::Align(
track->GetString(constants::Track::ALBUM),
text::AlignLeft,
kAlbumColWidth);
std::string artist = text::Align(
track->GetString(constants::Track::ARTIST),
text::AlignLeft,
kArtistColWidth);
int titleWidth =
(int) width -
(int) trackColWidth -
kDurationColWidth -
kAlbumColWidth -
kArtistColWidth -
(int) u8cols(rating) -
(4 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(
track->GetString(constants::Track::TITLE),
text::AlignLeft,
(int) titleWidth);
return u8fmt(
"%s %s%s %s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
album.c_str(),
artist.c_str());
};
}
namespace musik {
namespace cube {
namespace TrackRowRenderers {
const Renderer Get(Type type) {
switch (type) {
case Type::AlbumSort: return AlbumSort::renderer;
case Type::NowPlaying: return NowPlaying::renderer;
}
throw std::runtime_error("invalid type specified to TrackRowRenderers::Get");
}
}
}
}
<commit_msg>Made it a bit easier to tweak skeleton rows.<commit_after>//////////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2004-2020 musikcube team
//
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * 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.
//
// * Neither the name of the author nor the names of other 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 <stdafx.h>
#include "TrackRowRenderers.h"
#include <cursespp/Colors.h>
#include <cursespp/SingleLineEntry.h>
#include <cursespp/Text.h>
#include <musikcore/support/PreferenceKeys.h>
#include <musikcore/library/LocalLibraryConstants.h>
#include <musikcore/support/Duration.h>
#include <app/util/Rating.h>
#include <app/util/PreferenceKeys.h>
#include <math.h>
using namespace musik::core;
using namespace musik::core::library;
using namespace musik::cube;
using namespace musik::cube::TrackRowRenderers;
using namespace cursespp;
#define DIGITS(x) (x > 9 ? (int) log10((double) x) + 1 : 1)
static const bool kEnableSkeletonRows = true;
static const std::string kSkeletonChar = "░";
static const int kDurationColWidth = 5; /* 00:00 */
static const int kRatingBreakpointWidth = 90;
/* this method does a couple things slower than it probably should, but it
shouldn't cause any issues. TODO: make this better? does it matter? */
static inline std::string getRatingForTrack(TrackPtr track, size_t width) {
if (width <= kRatingBreakpointWidth) {
return "";
}
auto p = Preferences::ForComponent(musik::core::prefs::components::Settings);
if (p->GetBool(musik::cube::prefs::keys::DisableRatingColumn, false)) {
return "";
}
const int rating = std::max(0, std::min(5, track->GetInt32("rating", 0)));
return " " + getRatingString(rating);
}
static std::string placeholder(int width) {
std::string result;
for (int i = 0; i < width; i++) {
result += kSkeletonChar;
}
return result;
}
namespace AlbumSort {
static const int kTrackColWidth = 3;
static const int kArtistColWidth = 17;
static const int kRatingColumnWidth = 5;
static std::string skeleton(TrackPtr track, size_t width) {
auto const id = track->GetId();
std::string rating = width <= kRatingBreakpointWidth ? "" : getRatingString(0);
std::string trackNum = text::Align(placeholder(2), text::AlignRight, kTrackColWidth);
std::string duration = text::Align("0:00", text::AlignRight, kDurationColWidth);
std::string artist = text::Align(placeholder(1 + (id % (kArtistColWidth - 2))), text::AlignLeft, kArtistColWidth);
int titleWidth =
(int) width -
(int) kTrackColWidth -
kDurationColWidth -
kArtistColWidth -
(int) u8len(rating) -
(3 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(placeholder(1 + (id % ((int64_t) titleWidth - 2))), text::AlignLeft, (int) titleWidth);
return u8fmt(
"%s %s%s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
artist.c_str());
}
static const Renderer renderer = [](TrackPtr track, size_t index, size_t width, TrackNumType type) -> std::string {
if (track->GetMetadataState() != musik::core::sdk::MetadataState::Loaded) {
return kEnableSkeletonRows ? skeleton(track, width) : std::string(width, ' ');;
}
std::string trackNum;
std::string rating = getRatingForTrack(track, width);
int trackColWidth = kTrackColWidth;
if (type == TrackNumType::Metadata) {
trackNum = text::Align(
track->GetString(constants::Track::TRACK_NUM),
text::AlignRight,
kTrackColWidth);
}
else {
trackColWidth = std::max(kTrackColWidth, DIGITS(index + 1));
trackNum = text::Align(std::to_string(index + 1), text::AlignRight, trackColWidth);
}
std::string duration = text::Align(
musik::core::duration::Duration(track->GetString(constants::Track::DURATION)),
text::AlignRight,
kDurationColWidth);
std::string artist = text::Align(
track->GetString(constants::Track::ARTIST),
text::AlignLeft,
kArtistColWidth);
int titleWidth = 0;
titleWidth =
(int) width -
(int) trackColWidth -
kDurationColWidth -
kArtistColWidth -
(int) u8len(rating) -
(3 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(
track->GetString(constants::Track::TITLE),
text::AlignLeft,
(int) titleWidth);
return u8fmt(
"%s %s%s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
artist.c_str());
};
}
namespace NowPlaying {
static const int kTrackColWidth = 3;
static const int kArtistColWidth = 14;
static const int kAlbumColWidth = 14;
static std::string skeleton(TrackPtr track, size_t width) {
auto const id = track->GetId();
std::string rating = width <= kRatingBreakpointWidth ? "" : getRatingString(0);
std::string trackNum = text::Align(placeholder(2), text::AlignRight, kTrackColWidth);
std::string duration = text::Align("0:00", text::AlignRight, kDurationColWidth);
std::string album = text::Align(placeholder(1 + (id % (kAlbumColWidth - 2))), text::AlignLeft, kAlbumColWidth);
std::string artist = text::Align(placeholder(1 + (id % (kArtistColWidth - 2))), text::AlignLeft, kArtistColWidth);
int titleWidth =
(int)width -
(int)kTrackColWidth -
kDurationColWidth -
kAlbumColWidth -
kArtistColWidth -
(int)u8len(rating) -
(4 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(placeholder(1 + (id % ((int64_t) titleWidth - 2))), text::AlignLeft, (int) titleWidth);
return u8fmt(
"%s %s%s %s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
album.c_str(),
artist.c_str());
}
static const Renderer renderer = [](TrackPtr track, size_t index, size_t width, TrackNumType type) -> std::string {
if (track->GetMetadataState() != musik::core::sdk::MetadataState::Loaded) {
return kEnableSkeletonRows ? skeleton(track, width) : std::string(width, ' ');
}
const size_t trackColWidth = std::max(kTrackColWidth, DIGITS(index + 1));
std::string trackNum = text::Align(std::to_string(index + 1), text::AlignRight, trackColWidth);
std::string rating = getRatingForTrack(track, width);
std::string duration = text::Align(
duration::Duration(track->GetString(constants::Track::DURATION)),
text::AlignRight,
kDurationColWidth);
std::string album = text::Align(
track->GetString(constants::Track::ALBUM),
text::AlignLeft,
kAlbumColWidth);
std::string artist = text::Align(
track->GetString(constants::Track::ARTIST),
text::AlignLeft,
kArtistColWidth);
int titleWidth =
(int) width -
(int) trackColWidth -
kDurationColWidth -
kAlbumColWidth -
kArtistColWidth -
(int) u8cols(rating) -
(4 * 3); /* 3 = spacing */
titleWidth = std::max(0, titleWidth);
std::string title = text::Align(
track->GetString(constants::Track::TITLE),
text::AlignLeft,
(int) titleWidth);
return u8fmt(
"%s %s%s %s %s %s",
trackNum.c_str(),
title.c_str(),
rating.c_str(),
duration.c_str(),
album.c_str(),
artist.c_str());
};
}
namespace musik {
namespace cube {
namespace TrackRowRenderers {
const Renderer Get(Type type) {
switch (type) {
case Type::AlbumSort: return AlbumSort::renderer;
case Type::NowPlaying: return NowPlaying::renderer;
}
throw std::runtime_error("invalid type specified to TrackRowRenderers::Get");
}
}
}
}
<|endoftext|> |
<commit_before>/**
* Copyright (c) 2016-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*/
#include "AccessMarking.h"
#include <unordered_map>
#include "VirtualScope.h"
#include "DexUtil.h"
#include "Mutators.h"
#include "ReachableClasses.h"
#include "Resolver.h"
#include "Walkers.h"
namespace {
size_t mark_classes_final(const DexStoresVector& stores) {
size_t n_classes_finalized = 0;
for (auto const& dex : DexStoreClassesIterator(stores)) {
for (auto const& cls : dex) {
if (keep(cls) || is_abstract(cls) || is_final(cls)) continue;
auto const& children = get_children(cls->get_type());
if (children.empty()) {
TRACE(ACCESS, 2, "Finalizing class: %s\n", SHOW(cls));
set_final(cls);
++n_classes_finalized;
}
}
}
return n_classes_finalized;
}
const DexMethod* find_override(const DexMethod* method, const DexClass* cls) {
std::vector<const DexType*> children;
get_all_children(cls->get_type(), children);
for (auto const& childtype : children) {
auto const& child = type_class(childtype);
assert(child);
for (auto const& child_method : child->get_vmethods()) {
if (signatures_match(method, child_method)) {
return child_method;
}
}
}
return nullptr;
}
size_t mark_methods_final(const DexStoresVector& stores) {
size_t n_methods_finalized = 0;
for (auto const& dex : DexStoreClassesIterator(stores)) {
for (auto const& cls : dex) {
for (auto const& method : cls->get_vmethods()) {
if (keep(method) || is_abstract(method) || is_final(method)) {
continue;
}
if (!find_override(method, cls)) {
TRACE(ACCESS, 2, "Finalizing method: %s\n", SHOW(method));
set_final(method);
++n_methods_finalized;
}
}
}
}
return n_methods_finalized;
}
std::vector<DexMethod*> direct_methods(const std::vector<DexClass*>& scope) {
std::vector<DexMethod*> ret;
for (auto cls : scope) {
for (auto m : cls->get_dmethods()) {
ret.push_back(m);
}
}
return ret;
}
bool uses_this(const DexMethod* method) {
auto const& code = method->get_code();
if (!code) return false;
auto const this_reg = code->get_registers_size() - code->get_ins_size();
for (auto const& insn : code->get_instructions()) {
if (insn->has_range()) {
if (this_reg >= insn->range_base() &&
this_reg < (insn->range_base() + insn->range_size())) {
return true;
}
}
for (unsigned i = 0; i < insn->srcs_size(); i++) {
if (this_reg == insn->src(i)) return true;
}
}
return false;
}
std::unordered_set<DexMethod*> find_static_methods(
const std::vector<DexMethod*>& candidates
) {
std::unordered_set<DexMethod*> staticized;
for (auto const& method : candidates) {
if (is_static(method) ||
uses_this(method) ||
keep(method) ||
method->is_external() ||
is_abstract(method)) {
continue;
}
staticized.emplace(method);
}
return staticized;
}
void fix_call_sites(
const std::vector<DexClass*>& scope,
const std::unordered_set<DexMethod*>& statics
) {
walk_opcodes(
scope,
[](DexMethod*) { return true; },
[&](DexMethod*, DexInstruction* inst) {
if (!inst->has_methods()) return;
auto mi = static_cast<DexOpcodeMethod*>(inst);
auto method = mi->get_method();
if (!method->is_concrete()) {
method = resolve_method(method, MethodSearch::Any);
}
if (statics.count(method)) {
mi->rewrite_method(method);
if (is_invoke_range(inst->opcode())) {
if (mi->range_size() == 1) {
mi->set_opcode(OPCODE_INVOKE_STATIC);
mi->set_arg_word_count(0);
} else {
mi->set_opcode(OPCODE_INVOKE_STATIC_RANGE);
mi->set_range_base(mi->range_base() + 1);
mi->set_range_size(mi->range_size() - 1);
}
} else {
mi->set_opcode(OPCODE_INVOKE_STATIC);
auto nargs = mi->arg_word_count();
mi->set_arg_word_count(nargs - 1);
for (uint16_t i = 0; i < nargs - 1; i++) {
mi->set_src(i, mi->src(i + 1));
}
}
}
}
);
}
void mark_methods_static(const std::unordered_set<DexMethod*>& statics) {
for (auto method : statics) {
TRACE(ACCESS, 2, "Staticized method: %s\n", SHOW(method));
mutators::make_static(method, mutators::KeepThis::No);
}
}
std::unordered_set<DexMethod*> find_private_methods(
const std::vector<DexClass*>& scope,
const std::vector<DexMethod*>& cv
) {
std::unordered_set<DexMethod*> candidates;
for (auto m : cv) {
TRACE(ACCESS, 3, "Considering for privatization: %s\n", SHOW(m));
if (!is_clinit(m) && !keep(m) && !is_abstract(m) && !is_private(m)) {
candidates.emplace(m);
}
}
walk_opcodes(
scope,
[](DexMethod*) { return true; },
[&](DexMethod* caller, DexInstruction* inst) {
if (!inst->has_methods()) return;
auto mi = static_cast<DexOpcodeMethod*>(inst);
auto callee = mi->get_method();
if (!callee->is_concrete()) {
callee = resolve_method(callee, MethodSearch::Any);
if (!callee) return;
}
if (callee->get_class() == caller->get_class()) {
return;
}
candidates.erase(callee);
}
);
return candidates;
}
void fix_call_sites_private(
const std::vector<DexClass*>& scope,
const std::unordered_set<DexMethod*>& privates
) {
walk_opcodes(
scope,
[](DexMethod*) { return true; },
[&](DexMethod*, DexInstruction* inst) {
if (!inst->has_methods()) return;
auto mi = static_cast<DexOpcodeMethod*>(inst);
auto callee = mi->get_method();
if (!callee->is_concrete()) {
callee = resolve_method(callee, MethodSearch::Any);
}
if (privates.count(callee)) {
mi->rewrite_method(callee);
if (!is_static(callee)) {
mi->set_opcode(
is_invoke_range(mi->opcode())
? OPCODE_INVOKE_DIRECT_RANGE
: OPCODE_INVOKE_DIRECT);
}
}
}
);
}
void mark_methods_private(const std::unordered_set<DexMethod*>& privates) {
for (auto method : privates) {
TRACE(ACCESS, 2, "Privatized method: %s\n", SHOW(method));
auto cls = type_class(method->get_class());
cls->remove_method(method);
method->set_virtual(false);
set_private(method);
cls->add_method(method);
}
}
}
void AccessMarkingPass::run_pass(
DexStoresVector& stores,
ConfigFiles& cfg,
PassManager& pm
) {
if (m_finalize_classes) {
auto n_classes_final = mark_classes_final(stores);
pm.incr_metric("finalized_classes", n_classes_final);
TRACE(ACCESS, 1, "Finalized %lu classes\n", n_classes_final);
}
if (m_finalize_methods) {
auto n_methods_final = mark_methods_final(stores);
pm.incr_metric("finalized_methods", n_methods_final);
TRACE(ACCESS, 1, "Finalized %lu methods\n", n_methods_final);
}
auto scope = build_class_scope(stores);
auto candidates = devirtualize(scope);
auto dmethods = direct_methods(scope);
candidates.insert(candidates.end(), dmethods.begin(), dmethods.end());
if (m_staticize_methods) {
auto static_methods = find_static_methods(candidates);
fix_call_sites(scope, static_methods);
mark_methods_static(static_methods);
pm.incr_metric("staticized_methods", static_methods.size());
TRACE(ACCESS, 1, "Staticized %lu methods\n", static_methods.size());
}
if (m_privatize_methods) {
auto privates = find_private_methods(scope, candidates);
fix_call_sites_private(scope, privates);
mark_methods_private(privates);
pm.incr_metric("privatized_methods", privates.size());
TRACE(ACCESS, 1, "Privatized %lu methods\n", privates.size());
}
TRACE(ACCESS, 42, "dummy");
}
static AccessMarkingPass s_pass;
<commit_msg>Remove the dummy code<commit_after>/**
* Copyright (c) 2016-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*/
#include "AccessMarking.h"
#include <unordered_map>
#include "VirtualScope.h"
#include "DexUtil.h"
#include "Mutators.h"
#include "ReachableClasses.h"
#include "Resolver.h"
#include "Walkers.h"
namespace {
size_t mark_classes_final(const DexStoresVector& stores) {
size_t n_classes_finalized = 0;
for (auto const& dex : DexStoreClassesIterator(stores)) {
for (auto const& cls : dex) {
if (keep(cls) || is_abstract(cls) || is_final(cls)) continue;
auto const& children = get_children(cls->get_type());
if (children.empty()) {
TRACE(ACCESS, 2, "Finalizing class: %s\n", SHOW(cls));
set_final(cls);
++n_classes_finalized;
}
}
}
return n_classes_finalized;
}
const DexMethod* find_override(const DexMethod* method, const DexClass* cls) {
std::vector<const DexType*> children;
get_all_children(cls->get_type(), children);
for (auto const& childtype : children) {
auto const& child = type_class(childtype);
assert(child);
for (auto const& child_method : child->get_vmethods()) {
if (signatures_match(method, child_method)) {
return child_method;
}
}
}
return nullptr;
}
size_t mark_methods_final(const DexStoresVector& stores) {
size_t n_methods_finalized = 0;
for (auto const& dex : DexStoreClassesIterator(stores)) {
for (auto const& cls : dex) {
for (auto const& method : cls->get_vmethods()) {
if (keep(method) || is_abstract(method) || is_final(method)) {
continue;
}
if (!find_override(method, cls)) {
TRACE(ACCESS, 2, "Finalizing method: %s\n", SHOW(method));
set_final(method);
++n_methods_finalized;
}
}
}
}
return n_methods_finalized;
}
std::vector<DexMethod*> direct_methods(const std::vector<DexClass*>& scope) {
std::vector<DexMethod*> ret;
for (auto cls : scope) {
for (auto m : cls->get_dmethods()) {
ret.push_back(m);
}
}
return ret;
}
bool uses_this(const DexMethod* method) {
auto const& code = method->get_code();
if (!code) return false;
auto const this_reg = code->get_registers_size() - code->get_ins_size();
for (auto const& insn : code->get_instructions()) {
if (insn->has_range()) {
if (this_reg >= insn->range_base() &&
this_reg < (insn->range_base() + insn->range_size())) {
return true;
}
}
for (unsigned i = 0; i < insn->srcs_size(); i++) {
if (this_reg == insn->src(i)) return true;
}
}
return false;
}
std::unordered_set<DexMethod*> find_static_methods(
const std::vector<DexMethod*>& candidates
) {
std::unordered_set<DexMethod*> staticized;
for (auto const& method : candidates) {
if (is_static(method) ||
uses_this(method) ||
keep(method) ||
method->is_external() ||
is_abstract(method)) {
continue;
}
staticized.emplace(method);
}
return staticized;
}
void fix_call_sites(
const std::vector<DexClass*>& scope,
const std::unordered_set<DexMethod*>& statics
) {
walk_opcodes(
scope,
[](DexMethod*) { return true; },
[&](DexMethod*, DexInstruction* inst) {
if (!inst->has_methods()) return;
auto mi = static_cast<DexOpcodeMethod*>(inst);
auto method = mi->get_method();
if (!method->is_concrete()) {
method = resolve_method(method, MethodSearch::Any);
}
if (statics.count(method)) {
mi->rewrite_method(method);
if (is_invoke_range(inst->opcode())) {
if (mi->range_size() == 1) {
mi->set_opcode(OPCODE_INVOKE_STATIC);
mi->set_arg_word_count(0);
} else {
mi->set_opcode(OPCODE_INVOKE_STATIC_RANGE);
mi->set_range_base(mi->range_base() + 1);
mi->set_range_size(mi->range_size() - 1);
}
} else {
mi->set_opcode(OPCODE_INVOKE_STATIC);
auto nargs = mi->arg_word_count();
mi->set_arg_word_count(nargs - 1);
for (uint16_t i = 0; i < nargs - 1; i++) {
mi->set_src(i, mi->src(i + 1));
}
}
}
}
);
}
void mark_methods_static(const std::unordered_set<DexMethod*>& statics) {
for (auto method : statics) {
TRACE(ACCESS, 2, "Staticized method: %s\n", SHOW(method));
mutators::make_static(method, mutators::KeepThis::No);
}
}
std::unordered_set<DexMethod*> find_private_methods(
const std::vector<DexClass*>& scope,
const std::vector<DexMethod*>& cv
) {
std::unordered_set<DexMethod*> candidates;
for (auto m : cv) {
TRACE(ACCESS, 3, "Considering for privatization: %s\n", SHOW(m));
if (!is_clinit(m) && !keep(m) && !is_abstract(m) && !is_private(m)) {
candidates.emplace(m);
}
}
walk_opcodes(
scope,
[](DexMethod*) { return true; },
[&](DexMethod* caller, DexInstruction* inst) {
if (!inst->has_methods()) return;
auto mi = static_cast<DexOpcodeMethod*>(inst);
auto callee = mi->get_method();
if (!callee->is_concrete()) {
callee = resolve_method(callee, MethodSearch::Any);
if (!callee) return;
}
if (callee->get_class() == caller->get_class()) {
return;
}
candidates.erase(callee);
}
);
return candidates;
}
void fix_call_sites_private(
const std::vector<DexClass*>& scope,
const std::unordered_set<DexMethod*>& privates
) {
walk_opcodes(
scope,
[](DexMethod*) { return true; },
[&](DexMethod*, DexInstruction* inst) {
if (!inst->has_methods()) return;
auto mi = static_cast<DexOpcodeMethod*>(inst);
auto callee = mi->get_method();
if (!callee->is_concrete()) {
callee = resolve_method(callee, MethodSearch::Any);
}
if (privates.count(callee)) {
mi->rewrite_method(callee);
if (!is_static(callee)) {
mi->set_opcode(
is_invoke_range(mi->opcode())
? OPCODE_INVOKE_DIRECT_RANGE
: OPCODE_INVOKE_DIRECT);
}
}
}
);
}
void mark_methods_private(const std::unordered_set<DexMethod*>& privates) {
for (auto method : privates) {
TRACE(ACCESS, 2, "Privatized method: %s\n", SHOW(method));
auto cls = type_class(method->get_class());
cls->remove_method(method);
method->set_virtual(false);
set_private(method);
cls->add_method(method);
}
}
}
void AccessMarkingPass::run_pass(
DexStoresVector& stores,
ConfigFiles& cfg,
PassManager& pm
) {
if (m_finalize_classes) {
auto n_classes_final = mark_classes_final(stores);
pm.incr_metric("finalized_classes", n_classes_final);
TRACE(ACCESS, 1, "Finalized %lu classes\n", n_classes_final);
}
if (m_finalize_methods) {
auto n_methods_final = mark_methods_final(stores);
pm.incr_metric("finalized_methods", n_methods_final);
TRACE(ACCESS, 1, "Finalized %lu methods\n", n_methods_final);
}
auto scope = build_class_scope(stores);
auto candidates = devirtualize(scope);
auto dmethods = direct_methods(scope);
candidates.insert(candidates.end(), dmethods.begin(), dmethods.end());
if (m_staticize_methods) {
auto static_methods = find_static_methods(candidates);
fix_call_sites(scope, static_methods);
mark_methods_static(static_methods);
pm.incr_metric("staticized_methods", static_methods.size());
TRACE(ACCESS, 1, "Staticized %lu methods\n", static_methods.size());
}
if (m_privatize_methods) {
auto privates = find_private_methods(scope, candidates);
fix_call_sites_private(scope, privates);
mark_methods_private(privates);
pm.incr_metric("privatized_methods", privates.size());
TRACE(ACCESS, 1, "Privatized %lu methods\n", privates.size());
}
}
static AccessMarkingPass s_pass;
<|endoftext|> |
<commit_before>// Copyright 2004-present Facebook. All Rights Reserved.
#include "TcpConnectionAcceptor.h"
#include <folly/ThreadName.h>
#include <folly/io/async/ScopedEventBaseThread.h>
#include "src/framing/FramedDuplexConnection.h"
#include "src/transports/tcp/TcpDuplexConnection.h"
namespace rsocket {
class TcpConnectionAcceptor::SocketCallback
: public folly::AsyncServerSocket::AcceptCallback {
public:
explicit SocketCallback(OnDuplexConnectionAccept& onAccept)
: onAccept_{onAccept} {}
void connectionAccepted(
int fd,
const folly::SocketAddress& address) noexcept override {
VLOG(1) << "Accepting TCP connection from " << address << " on FD " << fd;
folly::AsyncSocket::UniquePtr socket(
new folly::AsyncSocket(eventBase(), fd));
auto connection = std::make_unique<TcpDuplexConnection>(
std::move(socket), inlineExecutor());
auto framedConnection = std::make_unique<FramedDuplexConnection>(
std::move(connection), inlineExecutor());
onAccept_(std::move(framedConnection), *eventBase());
}
void acceptError(const std::exception& ex) noexcept override {
VLOG(1) << "TCP error: " << ex.what();
}
folly::EventBase* eventBase() const {
return thread_.getEventBase();
}
private:
/// The thread running this callback.
folly::ScopedEventBaseThread thread_;
/// Reference to the ConnectionAcceptor's callback.
OnDuplexConnectionAccept& onAccept_;
};
////////////////////////////////////////////////////////////////////////////////
TcpConnectionAcceptor::TcpConnectionAcceptor(Options options)
: options_(std::move(options)) {}
TcpConnectionAcceptor::~TcpConnectionAcceptor() {
if (serverThread_) {
stop();
}
}
////////////////////////////////////////////////////////////////////////////////
folly::Future<folly::Unit> TcpConnectionAcceptor::start(
OnDuplexConnectionAccept onAccept) {
if (onAccept_ != nullptr) {
return folly::makeFuture<folly::Unit>(
std::runtime_error("TcpConnectionAcceptor::start() already called"));
}
onAccept_ = std::move(onAccept);
serverThread_ = std::make_unique<folly::ScopedEventBaseThread>();
serverThread_->getEventBase()->runInEventBaseThread(
[] { folly::setThreadName("TcpConnectionAcceptor.Listener"); });
callbacks_.reserve(options_.threads);
for (size_t i = 0; i < options_.threads; ++i) {
callbacks_.push_back(std::make_unique<SocketCallback>(onAccept_));
callbacks_[i]->eventBase()->runInEventBaseThread(
[] { folly::setThreadName("TcpConnectionAcceptor.Worker"); });
}
LOG(INFO) << "Starting TCP listener on port " << options_.port << " with "
<< options_.threads << " request threads";
serverSocket_.reset(
new folly::AsyncServerSocket(serverThread_->getEventBase()));
serverThread_->getEventBase()->runInEventBaseThread([this] {
folly::SocketAddress addr;
addr.setFromLocalPort(options_.port);
serverSocket_->bind(addr);
for (auto const& callback : callbacks_) {
serverSocket_->addAcceptCallback(callback.get(), callback->eventBase());
}
serverSocket_->listen(options_.backlog);
serverSocket_->startAccepting();
for (auto& i : serverSocket_->getAddresses()) {
LOG(INFO) << "Listening on " << i.describe();
}
});
return folly::unit;
}
void TcpConnectionAcceptor::stop() {
LOG(INFO) << "Shutting down TCP listener";
serverThread_->getEventBase()->runInEventBaseThread(
[this] { serverSocket_.reset(); });
serverThread_.reset();
}
}
<commit_msg>TCP server should be able support any version<commit_after>// Copyright 2004-present Facebook. All Rights Reserved.
#include "TcpConnectionAcceptor.h"
#include <folly/ThreadName.h>
#include <folly/io/async/ScopedEventBaseThread.h>
#include "src/framing/FramedDuplexConnection.h"
#include "src/transports/tcp/TcpDuplexConnection.h"
namespace rsocket {
class TcpConnectionAcceptor::SocketCallback
: public folly::AsyncServerSocket::AcceptCallback {
public:
explicit SocketCallback(OnDuplexConnectionAccept& onAccept)
: onAccept_{onAccept} {}
void connectionAccepted(
int fd,
const folly::SocketAddress& address) noexcept override {
VLOG(1) << "Accepting TCP connection from " << address << " on FD " << fd;
folly::AsyncSocket::UniquePtr socket(
new folly::AsyncSocket(eventBase(), fd));
auto connection = std::make_unique<TcpDuplexConnection>(
std::move(socket), inlineExecutor());
auto framedConnection = std::make_unique<FramedDuplexConnection>(
std::move(connection), ProtocolVersion::Unknown, inlineExecutor());
onAccept_(std::move(framedConnection), *eventBase());
}
void acceptError(const std::exception& ex) noexcept override {
VLOG(1) << "TCP error: " << ex.what();
}
folly::EventBase* eventBase() const {
return thread_.getEventBase();
}
private:
/// The thread running this callback.
folly::ScopedEventBaseThread thread_;
/// Reference to the ConnectionAcceptor's callback.
OnDuplexConnectionAccept& onAccept_;
};
////////////////////////////////////////////////////////////////////////////////
TcpConnectionAcceptor::TcpConnectionAcceptor(Options options)
: options_(std::move(options)) {}
TcpConnectionAcceptor::~TcpConnectionAcceptor() {
if (serverThread_) {
stop();
}
}
////////////////////////////////////////////////////////////////////////////////
folly::Future<folly::Unit> TcpConnectionAcceptor::start(
OnDuplexConnectionAccept onAccept) {
if (onAccept_ != nullptr) {
return folly::makeFuture<folly::Unit>(
std::runtime_error("TcpConnectionAcceptor::start() already called"));
}
onAccept_ = std::move(onAccept);
serverThread_ = std::make_unique<folly::ScopedEventBaseThread>();
serverThread_->getEventBase()->runInEventBaseThread(
[] { folly::setThreadName("TcpConnectionAcceptor.Listener"); });
callbacks_.reserve(options_.threads);
for (size_t i = 0; i < options_.threads; ++i) {
callbacks_.push_back(std::make_unique<SocketCallback>(onAccept_));
callbacks_[i]->eventBase()->runInEventBaseThread(
[] { folly::setThreadName("TcpConnectionAcceptor.Worker"); });
}
LOG(INFO) << "Starting TCP listener on port " << options_.port << " with "
<< options_.threads << " request threads";
serverSocket_.reset(
new folly::AsyncServerSocket(serverThread_->getEventBase()));
serverThread_->getEventBase()->runInEventBaseThread([this] {
folly::SocketAddress addr;
addr.setFromLocalPort(options_.port);
serverSocket_->bind(addr);
for (auto const& callback : callbacks_) {
serverSocket_->addAcceptCallback(callback.get(), callback->eventBase());
}
serverSocket_->listen(options_.backlog);
serverSocket_->startAccepting();
for (auto& i : serverSocket_->getAddresses()) {
LOG(INFO) << "Listening on " << i.describe();
}
});
return folly::unit;
}
void TcpConnectionAcceptor::stop() {
LOG(INFO) << "Shutting down TCP listener";
serverThread_->getEventBase()->runInEventBaseThread(
[this] { serverSocket_.reset(); });
serverThread_.reset();
}
}
<|endoftext|> |
<commit_before>/*
* This file is a part of Xpiks - cross platform application for
* keywording and uploading images for microstocks
* Copyright (C) 2014-2016 Taras Kushnir <kushnirTV@gmail.com>
*
* Xpiks is distributed under the GNU General Public License, version 3.0
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "curlftpuploader.h"
#include <QDebug>
#include <QFileInfo>
#include <cstdio>
#include <cstdlib>
#include "../../libcurl/include/curl/curl.h"
#define MINIMAL_PROGRESS_FUNCTIONALITY_INTERVAL 3
namespace Conectivity {
/* The MinGW headers are missing a few Win32 function definitions,
you shouldn't need this if you use VC++ */
#if defined(__MINGW32__) && !defined(__MINGW64__)
int __cdecl _snscanf(const char * input, size_t length, const char * format, ...);
#endif
/* parse headers for Content-Length */
size_t getcontentlengthfunc(void *ptr, size_t size, size_t nmemb, void *stream)
{
int r;
long len = 0;
#if defined(Q_OS_WIN)
/* _snscanf() is Win32 specific */
r = _snscanf((const char*)ptr, size * nmemb, "Content-Length: %ld\n", &len);
#else
r = std::sscanf((const char*)ptr, "Content-Length: %ld\n", &len);
#endif
if (r) /* Microsoft: we don't read the specs */
*((long *) stream) = len;
return size * nmemb;
}
/* discard downloaded data */
size_t discardfunc(void *ptr, size_t size, size_t nmemb, void *stream)
{
Q_UNUSED(stream);
Q_UNUSED(ptr);
return size * nmemb;
}
/* read data to upload */
size_t readfunc(void *ptr, size_t size, size_t nmemb, void *stream)
{
FILE *f = (FILE*)stream;
size_t n;
if (ferror(f))
return CURL_READFUNC_ABORT;
n = fread(ptr, size, nmemb, f) * size;
return n;
}
void fillCurlOptions(CURL *curlHandle, UploadContext *context, const QString &remoteUrl) {
curl_easy_setopt(curlHandle, CURLOPT_UPLOAD, 1L);
curl_easy_setopt(curlHandle, CURLOPT_URL, remoteUrl.toLocal8Bit().data());
curl_easy_setopt(curlHandle, CURLOPT_USERNAME, context->m_Username.toLocal8Bit().data());
curl_easy_setopt(curlHandle, CURLOPT_PASSWORD, context->m_Password.toLocal8Bit().data());
if (context->m_TimeoutSeconds) {
curl_easy_setopt(curlHandle, CURLOPT_FTP_RESPONSE_TIMEOUT, context->m_TimeoutSeconds);
}
curl_easy_setopt(curlHandle, CURLOPT_HEADERFUNCTION, getcontentlengthfunc);
curl_easy_setopt(curlHandle, CURLOPT_WRITEFUNCTION, discardfunc);
curl_easy_setopt(curlHandle, CURLOPT_READFUNCTION, readfunc);
if (!context->m_UsePassiveMode) {
curl_easy_setopt(curlHandle, CURLOPT_FTPPORT, "-"); /* disable passive mode */
}
}
QString sanitizeHost(const QString &inputHost) {
QString host = inputHost;
const QChar slash('/');
if (!host.endsWith(slash)) {
host.append(slash);
}
if (!host.startsWith(QLatin1String("ftp.")) &&
!host.startsWith(QLatin1String("ftp://"))) {
host = QLatin1String("ftp://") + host;
}
return host;
}
/* this is how the CURLOPT_XFERINFOFUNCTION callback works */
static int xferinfo(void *p,
curl_off_t dltotal, curl_off_t dlnow,
curl_off_t ultotal, curl_off_t ulnow)
{
CurlProgressReporter *progressReporter = (CurlProgressReporter *)p;
CURL *curl = progressReporter->getCurl();
double curtime = 0;
curl_easy_getinfo(curl, CURLINFO_TOTAL_TIME, &curtime);
/* under certain circumstances it may be desirable for certain functionality
to only run every N seconds, in order to do this the transaction time can
be used */
if ((curtime - progressReporter->getLastTime()) >= MINIMAL_PROGRESS_FUNCTIONALITY_INTERVAL) {
progressReporter->setLastTime(curtime);
progressReporter->updateProgress((double)ultotal, (double)ulnow);
}
return 0;
}
/* for libcurl older than 7.32.0 (CURLOPT_PROGRESSFUNCTION) */
static int older_progress(void *p,
double dltotal, double dlnow,
double ultotal, double ulnow)
{
return xferinfo(p,
(curl_off_t)dltotal,
(curl_off_t)dlnow,
(curl_off_t)ultotal,
(curl_off_t)ulnow);
}
void setCurlProgressCallback(CURL *curlHandle, CurlProgressReporter *progressReporter) {
curl_easy_setopt(curlHandle, CURLOPT_PROGRESSFUNCTION, older_progress);
/* pass the struct pointer into the progress function */
curl_easy_setopt(curlHandle, CURLOPT_PROGRESSDATA, progressReporter);
#if LIBCURL_VERSION_NUM >= 0x072000
/* xferinfo was introduced in 7.32.0, no earlier libcurl versions will
compile as they won't have the symbols around.
If built with a newer libcurl, but running with an older libcurl:
curl_easy_setopt() will fail in run-time trying to set the new
callback, making the older callback get used.
New libcurls will prefer the new callback and instead use that one even
if both callbacks are set. */
curl_easy_setopt(curlHandle, CURLOPT_XFERINFOFUNCTION, xferinfo);
/* pass the struct pointer into the xferinfo function, note that this is
an alias to CURLOPT_PROGRESSDATA */
curl_easy_setopt(curlHandle, CURLOPT_XFERINFODATA, progressReporter);
#endif
curl_easy_setopt(curlHandle, CURLOPT_NOPROGRESS, 0L);
}
bool uploadFile(CURL *curlHandle, UploadContext *context, CurlProgressReporter *progressReporter,
const QString &filepath, const QString &remoteUrl) {
bool result = false;
FILE *f;
long uploaded_len = 0;
CURLcode r = CURLE_GOT_NOTHING;
int c;
f = fopen(filepath.toLocal8Bit().data(), "rb");
if (f == NULL) {
qWarning() << "Failed to open file" << filepath;
return result;
}
fillCurlOptions(curlHandle, context, remoteUrl);
setCurlProgressCallback(curlHandle, progressReporter);
curl_easy_setopt(curlHandle, CURLOPT_READDATA, f);
curl_easy_setopt(curlHandle, CURLOPT_HEADERDATA, &uploaded_len);
for (c = 0; (r != CURLE_OK) && (c < context->m_RetriesCount); c++) {
/* are we resuming? */
if (c) { /* yes */
/* determine the length of the file already written */
/*
* With NOBODY and NOHEADER, libcurl will issue a SIZE
* command, but the only way to retrieve the result is
* to parse the returned Content-Length header. Thus,
* getcontentlengthfunc(). We need discardfunc() above
* because HEADER will dump the headers to stdout
* without it.
*/
curl_easy_setopt(curlHandle, CURLOPT_NOBODY, 1L);
curl_easy_setopt(curlHandle, CURLOPT_HEADER, 1L);
r = curl_easy_perform(curlHandle);
if (r != CURLE_OK) {
continue;
}
curl_easy_setopt(curlHandle, CURLOPT_NOBODY, 0L);
curl_easy_setopt(curlHandle, CURLOPT_HEADER, 0L);
fseek(f, uploaded_len, SEEK_SET);
curl_easy_setopt(curlHandle, CURLOPT_APPEND, 1L);
}
else { /* no */
curl_easy_setopt(curlHandle, CURLOPT_APPEND, 0L);
}
r = curl_easy_perform(curlHandle);
}
fclose(f);
result = (r == CURLE_OK);
if (!result) {
qWarning() << "Upload failed! Curl error:" << curl_easy_strerror(r);
}
return result;
}
CurlProgressReporter::CurlProgressReporter(void *curl):
QObject(),
m_LastTime(0.0),
m_Curl(curl)
{
}
void CurlProgressReporter::updateProgress(double ultotal, double ulnow) {
double progress = ulnow * 100.0 / ultotal;
emit progressChanged(progress);
}
CurlFtpUploader::CurlFtpUploader(UploadBatch *batchToUpload, QObject *parent) :
QObject(parent),
m_BatchToUpload(batchToUpload),
m_Cancel(false),
m_UploadedCount(0),
m_LastPercentage(0.0)
{
m_TotalCount = batchToUpload->getFilesToUpload().length();
}
void CurlFtpUploader::uploadBatch() {
CURL *curlHandle = NULL;
bool anyErrors = false;
UploadContext *context = m_BatchToUpload->getContext();
const QStringList &filesToUpload = m_BatchToUpload->getFilesToUpload();
int size = filesToUpload.size();
QString host = sanitizeHost(context->m_Host);
// TODO: do not call this from thread
//curl_global_init(CURL_GLOBAL_ALL);
curlHandle = curl_easy_init();
CurlProgressReporter progressReporter(curlHandle);
QObject::connect(&progressReporter, SIGNAL(progressChanged(double)),
this, SLOT(reportCurrentFileProgress(double)));
emit uploadStarted();
qDebug() << "Uploading" << size << "file(s) started for" << host;
for (int i = 0; i < size; ++i) {
if (m_Cancel) {
qWarning() << "CurlUploader: Cancelled. Breaking..." << host;
break;
}
const QString &filepath = filesToUpload.at(i);
QFileInfo fi(filepath);
QString remoteUrl = host + fi.fileName();
bool uploadSuccess = false;
try {
uploadSuccess = uploadFile(curlHandle, context, &progressReporter, filepath, remoteUrl);
} catch (...) {
qWarning() << "Upload CRASHED for file" << filepath;
}
if (!uploadSuccess) {
anyErrors = true;
emit transferFailed(filepath);
//m_FailedIndices.append(i);
}
// TODO: only update progress of not-failed uploads
if (uploadSuccess) {
m_UploadedCount++;
reportCurrentFileProgress(0.0);
}
}
emit uploadFinished(anyErrors);
qDebug() << "Uploading finished for" << host;
curl_easy_cleanup(curlHandle);
// TODO: do not call this from thread
//curl_global_cleanup();
}
void CurlFtpUploader::cancel() {
m_Cancel = true;
}
void CurlFtpUploader::reportCurrentFileProgress(double percent) {
double newProgress = m_UploadedCount*100.0 + percent;
newProgress /= m_TotalCount;
emit progressChanged(m_LastPercentage, newProgress);
m_LastPercentage = newProgress;
}
}
<commit_msg>Cosmetic improvements for progress reporting<commit_after>/*
* This file is a part of Xpiks - cross platform application for
* keywording and uploading images for microstocks
* Copyright (C) 2014-2016 Taras Kushnir <kushnirTV@gmail.com>
*
* Xpiks is distributed under the GNU General Public License, version 3.0
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "curlftpuploader.h"
#include <QDebug>
#include <QFileInfo>
#include <cstdio>
#include <cstdlib>
#include "../../libcurl/include/curl/curl.h"
#define MINIMAL_PROGRESS_FUNCTIONALITY_INTERVAL 3
namespace Conectivity {
/* The MinGW headers are missing a few Win32 function definitions,
you shouldn't need this if you use VC++ */
#if defined(__MINGW32__) && !defined(__MINGW64__)
int __cdecl _snscanf(const char * input, size_t length, const char * format, ...);
#endif
/* parse headers for Content-Length */
size_t getcontentlengthfunc(void *ptr, size_t size, size_t nmemb, void *stream)
{
int r;
long len = 0;
#if defined(Q_OS_WIN)
/* _snscanf() is Win32 specific */
r = _snscanf((const char*)ptr, size * nmemb, "Content-Length: %ld\n", &len);
#else
r = std::sscanf((const char*)ptr, "Content-Length: %ld\n", &len);
#endif
if (r) /* Microsoft: we don't read the specs */
*((long *) stream) = len;
return size * nmemb;
}
/* discard downloaded data */
size_t discardfunc(void *ptr, size_t size, size_t nmemb, void *stream)
{
Q_UNUSED(stream);
Q_UNUSED(ptr);
return size * nmemb;
}
/* read data to upload */
size_t readfunc(void *ptr, size_t size, size_t nmemb, void *stream)
{
FILE *f = (FILE*)stream;
size_t n;
if (ferror(f))
return CURL_READFUNC_ABORT;
n = fread(ptr, size, nmemb, f) * size;
return n;
}
void fillCurlOptions(CURL *curlHandle, UploadContext *context, const QString &remoteUrl) {
curl_easy_setopt(curlHandle, CURLOPT_UPLOAD, 1L);
curl_easy_setopt(curlHandle, CURLOPT_URL, remoteUrl.toLocal8Bit().data());
curl_easy_setopt(curlHandle, CURLOPT_USERNAME, context->m_Username.toLocal8Bit().data());
curl_easy_setopt(curlHandle, CURLOPT_PASSWORD, context->m_Password.toLocal8Bit().data());
if (context->m_TimeoutSeconds) {
curl_easy_setopt(curlHandle, CURLOPT_FTP_RESPONSE_TIMEOUT, context->m_TimeoutSeconds);
}
curl_easy_setopt(curlHandle, CURLOPT_HEADERFUNCTION, getcontentlengthfunc);
curl_easy_setopt(curlHandle, CURLOPT_WRITEFUNCTION, discardfunc);
curl_easy_setopt(curlHandle, CURLOPT_READFUNCTION, readfunc);
if (!context->m_UsePassiveMode) {
curl_easy_setopt(curlHandle, CURLOPT_FTPPORT, "-"); /* disable passive mode */
}
}
QString sanitizeHost(const QString &inputHost) {
QString host = inputHost;
const QChar slash('/');
if (!host.endsWith(slash)) {
host.append(slash);
}
if (!host.startsWith(QLatin1String("ftp.")) &&
!host.startsWith(QLatin1String("ftp://"))) {
host = QLatin1String("ftp://") + host;
}
return host;
}
/* this is how the CURLOPT_XFERINFOFUNCTION callback works */
static int xferinfo(void *p,
curl_off_t dltotal, curl_off_t dlnow,
curl_off_t ultotal, curl_off_t ulnow)
{
CurlProgressReporter *progressReporter = (CurlProgressReporter *)p;
CURL *curl = progressReporter->getCurl();
double curtime = 0;
curl_easy_getinfo(curl, CURLINFO_TOTAL_TIME, &curtime);
/* under certain circumstances it may be desirable for certain functionality
to only run every N seconds, in order to do this the transaction time can
be used */
if ((curtime - progressReporter->getLastTime()) >= MINIMAL_PROGRESS_FUNCTIONALITY_INTERVAL) {
progressReporter->setLastTime(curtime);
progressReporter->updateProgress((double)ultotal, (double)ulnow);
}
return 0;
}
/* for libcurl older than 7.32.0 (CURLOPT_PROGRESSFUNCTION) */
static int older_progress(void *p,
double dltotal, double dlnow,
double ultotal, double ulnow)
{
return xferinfo(p,
(curl_off_t)dltotal,
(curl_off_t)dlnow,
(curl_off_t)ultotal,
(curl_off_t)ulnow);
}
void setCurlProgressCallback(CURL *curlHandle, CurlProgressReporter *progressReporter) {
curl_easy_setopt(curlHandle, CURLOPT_PROGRESSFUNCTION, older_progress);
/* pass the struct pointer into the progress function */
curl_easy_setopt(curlHandle, CURLOPT_PROGRESSDATA, progressReporter);
#if LIBCURL_VERSION_NUM >= 0x072000
/* xferinfo was introduced in 7.32.0, no earlier libcurl versions will
compile as they won't have the symbols around.
If built with a newer libcurl, but running with an older libcurl:
curl_easy_setopt() will fail in run-time trying to set the new
callback, making the older callback get used.
New libcurls will prefer the new callback and instead use that one even
if both callbacks are set. */
curl_easy_setopt(curlHandle, CURLOPT_XFERINFOFUNCTION, xferinfo);
/* pass the struct pointer into the xferinfo function, note that this is
an alias to CURLOPT_PROGRESSDATA */
curl_easy_setopt(curlHandle, CURLOPT_XFERINFODATA, progressReporter);
#endif
curl_easy_setopt(curlHandle, CURLOPT_NOPROGRESS, 0L);
}
bool uploadFile(CURL *curlHandle, UploadContext *context, CurlProgressReporter *progressReporter,
const QString &filepath, const QString &remoteUrl) {
bool result = false;
FILE *f;
long uploaded_len = 0;
CURLcode r = CURLE_GOT_NOTHING;
int c;
f = fopen(filepath.toLocal8Bit().data(), "rb");
if (f == NULL) {
qWarning() << "Failed to open file" << filepath;
return result;
}
fillCurlOptions(curlHandle, context, remoteUrl);
setCurlProgressCallback(curlHandle, progressReporter);
curl_easy_setopt(curlHandle, CURLOPT_READDATA, f);
curl_easy_setopt(curlHandle, CURLOPT_HEADERDATA, &uploaded_len);
for (c = 0; (r != CURLE_OK) && (c < context->m_RetriesCount); c++) {
/* are we resuming? */
if (c) { /* yes */
/* determine the length of the file already written */
/*
* With NOBODY and NOHEADER, libcurl will issue a SIZE
* command, but the only way to retrieve the result is
* to parse the returned Content-Length header. Thus,
* getcontentlengthfunc(). We need discardfunc() above
* because HEADER will dump the headers to stdout
* without it.
*/
curl_easy_setopt(curlHandle, CURLOPT_NOBODY, 1L);
curl_easy_setopt(curlHandle, CURLOPT_HEADER, 1L);
r = curl_easy_perform(curlHandle);
if (r != CURLE_OK) {
continue;
}
curl_easy_setopt(curlHandle, CURLOPT_NOBODY, 0L);
curl_easy_setopt(curlHandle, CURLOPT_HEADER, 0L);
fseek(f, uploaded_len, SEEK_SET);
curl_easy_setopt(curlHandle, CURLOPT_APPEND, 1L);
}
else { /* no */
curl_easy_setopt(curlHandle, CURLOPT_APPEND, 0L);
}
r = curl_easy_perform(curlHandle);
}
fclose(f);
result = (r == CURLE_OK);
if (!result) {
qWarning() << "Upload failed! Curl error:" << curl_easy_strerror(r);
}
return result;
}
CurlProgressReporter::CurlProgressReporter(void *curl):
QObject(),
m_LastTime(0.0),
m_Curl(curl)
{
}
void CurlProgressReporter::updateProgress(double ultotal, double ulnow) {
double progress = ulnow * 100.0 / ultotal;
emit progressChanged(progress);
}
CurlFtpUploader::CurlFtpUploader(UploadBatch *batchToUpload, QObject *parent) :
QObject(parent),
m_BatchToUpload(batchToUpload),
m_Cancel(false),
m_UploadedCount(0),
m_LastPercentage(0.0)
{
m_TotalCount = batchToUpload->getFilesToUpload().length();
}
void CurlFtpUploader::uploadBatch() {
CURL *curlHandle = NULL;
bool anyErrors = false;
UploadContext *context = m_BatchToUpload->getContext();
const QStringList &filesToUpload = m_BatchToUpload->getFilesToUpload();
int size = filesToUpload.size();
QString host = sanitizeHost(context->m_Host);
// TODO: do not call this from thread
//curl_global_init(CURL_GLOBAL_ALL);
curlHandle = curl_easy_init();
CurlProgressReporter progressReporter(curlHandle);
QObject::connect(&progressReporter, SIGNAL(progressChanged(double)),
this, SLOT(reportCurrentFileProgress(double)));
emit uploadStarted();
qDebug() << "Uploading" << size << "file(s) started for" << host;
for (int i = 0; i < size; ++i) {
if (m_Cancel) {
qWarning() << "CurlUploader: Cancelled. Breaking..." << host;
break;
}
reportCurrentFileProgress(0.0);
const QString &filepath = filesToUpload.at(i);
QFileInfo fi(filepath);
QString remoteUrl = host + fi.fileName();
bool uploadSuccess = false;
try {
uploadSuccess = uploadFile(curlHandle, context, &progressReporter, filepath, remoteUrl);
} catch (...) {
qWarning() << "Upload CRASHED for file" << filepath;
}
if (!uploadSuccess) {
anyErrors = true;
emit transferFailed(filepath);
//m_FailedIndices.append(i);
}
// TODO: only update progress of not-failed uploads
if (uploadSuccess) {
m_UploadedCount++;
}
}
emit uploadFinished(anyErrors);
qDebug() << "Uploading finished for" << host;
curl_easy_cleanup(curlHandle);
// TODO: do not call this from thread
//curl_global_cleanup();
}
void CurlFtpUploader::cancel() {
m_Cancel = true;
}
void CurlFtpUploader::reportCurrentFileProgress(double percent) {
double newProgress = m_UploadedCount*100.0 + percent;
newProgress /= m_TotalCount;
emit progressChanged(m_LastPercentage, newProgress);
m_LastPercentage = newProgress;
}
}
<|endoftext|> |
<commit_before>/**************************************************************************
**
** This file is part of Qt Creator
**
** Copyright (c) 2009 Nokia Corporation and/or its subsidiary(-ies).
**
** Contact: Nokia Corporation (qt-info@nokia.com)
**
** Commercial Usage
**
** Licensees holding valid Qt Commercial licenses may use this file in
** accordance with the Qt Commercial License Agreement provided with the
** Software or, alternatively, in accordance with the terms contained in
** a written agreement between you and Nokia.
**
** GNU Lesser General Public License Usage
**
** Alternatively, this file may be used under the terms of the GNU Lesser
** General Public License version 2.1 as published by the Free Software
** Foundation and appearing in the file LICENSE.LGPL included in the
** packaging of this file. Please review the following information to
** ensure the GNU Lesser General Public License version 2.1 requirements
** will be met: http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html.
**
** If you are unsure which license is appropriate for your use, please
** contact the sales department at http://www.qtsoftware.com/contact.
**
**************************************************************************/
#include "makestep.h"
#include "cmakeprojectconstants.h"
#include "cmakeproject.h"
#include <QtGui/QFormLayout>
#include <QtGui/QGroupBox>
#include <QtGui/QCheckBox>
#include <QtGui/QLineEdit>
#include <QtGui/QListWidget>
using namespace CMakeProjectManager;
using namespace CMakeProjectManager::Internal;
MakeStep::MakeStep(CMakeProject *pro)
: AbstractMakeStep(pro), m_pro(pro)
{
m_percentProgress = QRegExp("^\\[\\s*(\\d*)%\\]");
}
MakeStep::~MakeStep()
{
}
bool MakeStep::init(const QString &buildConfiguration)
{
setBuildParser(m_pro->buildParser(buildConfiguration));
setEnabled(buildConfiguration, true);
setWorkingDirectory(buildConfiguration, m_pro->buildDirectory(buildConfiguration));
setCommand(buildConfiguration, m_pro->toolChain(buildConfiguration)->makeCommand());
if (!value(buildConfiguration, "cleanConfig").isValid() &&value("clean").isValid() && value("clean").toBool()) {
// Import old settings
setValue(buildConfiguration, "cleanConfig", true);
setAdditionalArguments(buildConfiguration, QStringList() << "clean");
}
QStringList arguments = value(buildConfiguration, "buildTargets").toStringList();
arguments << additionalArguments(buildConfiguration);
setArguments(buildConfiguration, arguments); // TODO
setEnvironment(buildConfiguration, m_pro->environment(buildConfiguration));
setIgnoreReturnValue(buildConfiguration, value(buildConfiguration, "cleanConfig").isValid());
return AbstractMakeStep::init(buildConfiguration);
}
void MakeStep::run(QFutureInterface<bool> &fi)
{
m_futureInterface = &fi;
m_futureInterface->setProgressRange(0, 100);
AbstractMakeStep::run(fi);
m_futureInterface->setProgressValue(100);
m_futureInterface->reportFinished();
m_futureInterface = 0;
}
QString MakeStep::name()
{
return Constants::MAKESTEP;
}
QString MakeStep::displayName()
{
return "Make";
}
ProjectExplorer::BuildStepConfigWidget *MakeStep::createConfigWidget()
{
return new MakeStepConfigWidget(this);
}
bool MakeStep::immutable() const
{
return true;
}
void MakeStep::stdOut(const QString &line)
{
if (m_percentProgress.indexIn(line) != -1) {
bool ok = false;
int percent = m_percentProgress.cap(1).toInt(&ok);;
if (ok)
m_futureInterface->setProgressValue(percent);
}
AbstractMakeStep::stdOut(line);
}
CMakeProject *MakeStep::project() const
{
return m_pro;
}
bool MakeStep::buildsTarget(const QString &buildConfiguration, const QString &target) const
{
return value(buildConfiguration, "buildTargets").toStringList().contains(target);
}
void MakeStep::setBuildTarget(const QString &buildConfiguration, const QString &target, bool on)
{
QStringList old = value(buildConfiguration, "buildTargets").toStringList();
if (on && !old.contains(target))
setValue(buildConfiguration, "buildTargets", old << target);
else if(!on && old.contains(target))
setValue(buildConfiguration, "buildTargets", old.removeOne(target));
}
QStringList MakeStep::additionalArguments(const QString &buildConfiguration) const
{
return value(buildConfiguration, "additionalArguments").toStringList();
}
void MakeStep::setAdditionalArguments(const QString &buildConfiguration, const QStringList &list)
{
setValue(buildConfiguration, "additionalArguments", list);
}
//
// MakeStepConfigWidget
//
MakeStepConfigWidget::MakeStepConfigWidget(MakeStep *makeStep)
: m_makeStep(makeStep)
{
QFormLayout *fl = new QFormLayout(this);
setLayout(fl);
m_additionalArguments = new QLineEdit(this);
fl->addRow(tr("Additional arguments:"), m_additionalArguments);
connect(m_additionalArguments, SIGNAL(textEdited(const QString &)), this, SLOT(additionalArgumentsEdited()));
m_targetsList = new QListWidget;
fl->addRow(tr("Targets:"), m_targetsList);
// TODO update this list also on rescans of the CMakeLists.txt
CMakeProject *pro = m_makeStep->project();
foreach(const QString& target, pro->targets()) {
QListWidgetItem *item = new QListWidgetItem(target, m_targetsList);
item->setFlags(item->flags() | Qt::ItemIsUserCheckable);
item->setCheckState(Qt::Unchecked);
}
connect(m_targetsList, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(itemChanged(QListWidgetItem*)));
}
void MakeStepConfigWidget::additionalArgumentsEdited()
{
m_makeStep->setAdditionalArguments(m_buildConfiguration, ProjectExplorer::Environment::parseCombinedArgString(m_additionalArguments->text()));
}
void MakeStepConfigWidget::itemChanged(QListWidgetItem *item)
{
m_makeStep->setBuildTarget(m_buildConfiguration, item->text(), item->checkState() & Qt::Checked);
}
QString MakeStepConfigWidget::displayName() const
{
return "Make";
}
void MakeStepConfigWidget::init(const QString &buildConfiguration)
{
if (!m_makeStep->value(buildConfiguration, "cleanConfig").isValid() && m_makeStep->value("clean").isValid() && m_makeStep->value("clean").toBool()) {
// Import old settings
m_makeStep->setValue(buildConfiguration, "cleanConfig", true);
m_makeStep->setAdditionalArguments(buildConfiguration, QStringList() << "clean");
}
// disconnect to make the changes to the items
disconnect(m_targetsList, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(itemChanged(QListWidgetItem*)));
m_buildConfiguration = buildConfiguration;
int count = m_targetsList->count();
for(int i = 0; i < count; ++i) {
QListWidgetItem *item = m_targetsList->item(i);
item->setCheckState(m_makeStep->buildsTarget(buildConfiguration, item->text()) ? Qt::Checked : Qt::Unchecked);
}
// and connect again
connect(m_targetsList, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(itemChanged(QListWidgetItem*)));
m_additionalArguments->setText(ProjectExplorer::Environment::joinArgumentList(m_makeStep->additionalArguments(m_buildConfiguration)));
}
//
// MakeStepFactory
//
bool MakeStepFactory::canCreate(const QString &name) const
{
return (Constants::MAKESTEP == name);
}
ProjectExplorer::BuildStep *MakeStepFactory::create(ProjectExplorer::Project *project, const QString &name) const
{
Q_ASSERT(name == Constants::MAKESTEP);
CMakeProject *pro = qobject_cast<CMakeProject *>(project);
Q_ASSERT(pro);
return new MakeStep(pro);
}
QStringList MakeStepFactory::canCreateForProject(ProjectExplorer::Project * /* pro */) const
{
return QStringList();
}
QString MakeStepFactory::displayNameForName(const QString & /* name */) const
{
return "Make";
}
<commit_msg>Another small tweak to the build settigns page.<commit_after>/**************************************************************************
**
** This file is part of Qt Creator
**
** Copyright (c) 2009 Nokia Corporation and/or its subsidiary(-ies).
**
** Contact: Nokia Corporation (qt-info@nokia.com)
**
** Commercial Usage
**
** Licensees holding valid Qt Commercial licenses may use this file in
** accordance with the Qt Commercial License Agreement provided with the
** Software or, alternatively, in accordance with the terms contained in
** a written agreement between you and Nokia.
**
** GNU Lesser General Public License Usage
**
** Alternatively, this file may be used under the terms of the GNU Lesser
** General Public License version 2.1 as published by the Free Software
** Foundation and appearing in the file LICENSE.LGPL included in the
** packaging of this file. Please review the following information to
** ensure the GNU Lesser General Public License version 2.1 requirements
** will be met: http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html.
**
** If you are unsure which license is appropriate for your use, please
** contact the sales department at http://www.qtsoftware.com/contact.
**
**************************************************************************/
#include "makestep.h"
#include "cmakeprojectconstants.h"
#include "cmakeproject.h"
#include <QtGui/QFormLayout>
#include <QtGui/QGroupBox>
#include <QtGui/QCheckBox>
#include <QtGui/QLineEdit>
#include <QtGui/QListWidget>
using namespace CMakeProjectManager;
using namespace CMakeProjectManager::Internal;
MakeStep::MakeStep(CMakeProject *pro)
: AbstractMakeStep(pro), m_pro(pro)
{
m_percentProgress = QRegExp("^\\[\\s*(\\d*)%\\]");
}
MakeStep::~MakeStep()
{
}
bool MakeStep::init(const QString &buildConfiguration)
{
setBuildParser(m_pro->buildParser(buildConfiguration));
setEnabled(buildConfiguration, true);
setWorkingDirectory(buildConfiguration, m_pro->buildDirectory(buildConfiguration));
setCommand(buildConfiguration, m_pro->toolChain(buildConfiguration)->makeCommand());
if (!value(buildConfiguration, "cleanConfig").isValid() &&value("clean").isValid() && value("clean").toBool()) {
// Import old settings
setValue(buildConfiguration, "cleanConfig", true);
setAdditionalArguments(buildConfiguration, QStringList() << "clean");
}
QStringList arguments = value(buildConfiguration, "buildTargets").toStringList();
arguments << additionalArguments(buildConfiguration);
setArguments(buildConfiguration, arguments); // TODO
setEnvironment(buildConfiguration, m_pro->environment(buildConfiguration));
setIgnoreReturnValue(buildConfiguration, value(buildConfiguration, "cleanConfig").isValid());
return AbstractMakeStep::init(buildConfiguration);
}
void MakeStep::run(QFutureInterface<bool> &fi)
{
m_futureInterface = &fi;
m_futureInterface->setProgressRange(0, 100);
AbstractMakeStep::run(fi);
m_futureInterface->setProgressValue(100);
m_futureInterface->reportFinished();
m_futureInterface = 0;
}
QString MakeStep::name()
{
return Constants::MAKESTEP;
}
QString MakeStep::displayName()
{
return "Make";
}
ProjectExplorer::BuildStepConfigWidget *MakeStep::createConfigWidget()
{
return new MakeStepConfigWidget(this);
}
bool MakeStep::immutable() const
{
return true;
}
void MakeStep::stdOut(const QString &line)
{
if (m_percentProgress.indexIn(line) != -1) {
bool ok = false;
int percent = m_percentProgress.cap(1).toInt(&ok);;
if (ok)
m_futureInterface->setProgressValue(percent);
}
AbstractMakeStep::stdOut(line);
}
CMakeProject *MakeStep::project() const
{
return m_pro;
}
bool MakeStep::buildsTarget(const QString &buildConfiguration, const QString &target) const
{
return value(buildConfiguration, "buildTargets").toStringList().contains(target);
}
void MakeStep::setBuildTarget(const QString &buildConfiguration, const QString &target, bool on)
{
QStringList old = value(buildConfiguration, "buildTargets").toStringList();
if (on && !old.contains(target))
setValue(buildConfiguration, "buildTargets", old << target);
else if(!on && old.contains(target))
setValue(buildConfiguration, "buildTargets", old.removeOne(target));
}
QStringList MakeStep::additionalArguments(const QString &buildConfiguration) const
{
return value(buildConfiguration, "additionalArguments").toStringList();
}
void MakeStep::setAdditionalArguments(const QString &buildConfiguration, const QStringList &list)
{
setValue(buildConfiguration, "additionalArguments", list);
}
//
// MakeStepConfigWidget
//
MakeStepConfigWidget::MakeStepConfigWidget(MakeStep *makeStep)
: m_makeStep(makeStep)
{
QFormLayout *fl = new QFormLayout(this);
setLayout(fl);
m_additionalArguments = new QLineEdit(this);
fl->addRow(tr("Additional arguments:"), m_additionalArguments);
connect(m_additionalArguments, SIGNAL(textEdited(const QString &)), this, SLOT(additionalArgumentsEdited()));
m_targetsList = new QListWidget;
m_targetsList->setMinimumHeight(200);
fl->addRow(tr("Targets:"), m_targetsList);
// TODO update this list also on rescans of the CMakeLists.txt
CMakeProject *pro = m_makeStep->project();
foreach(const QString& target, pro->targets()) {
QListWidgetItem *item = new QListWidgetItem(target, m_targetsList);
item->setFlags(item->flags() | Qt::ItemIsUserCheckable);
item->setCheckState(Qt::Unchecked);
}
connect(m_targetsList, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(itemChanged(QListWidgetItem*)));
}
void MakeStepConfigWidget::additionalArgumentsEdited()
{
m_makeStep->setAdditionalArguments(m_buildConfiguration, ProjectExplorer::Environment::parseCombinedArgString(m_additionalArguments->text()));
}
void MakeStepConfigWidget::itemChanged(QListWidgetItem *item)
{
m_makeStep->setBuildTarget(m_buildConfiguration, item->text(), item->checkState() & Qt::Checked);
}
QString MakeStepConfigWidget::displayName() const
{
return "Make";
}
void MakeStepConfigWidget::init(const QString &buildConfiguration)
{
if (!m_makeStep->value(buildConfiguration, "cleanConfig").isValid() && m_makeStep->value("clean").isValid() && m_makeStep->value("clean").toBool()) {
// Import old settings
m_makeStep->setValue(buildConfiguration, "cleanConfig", true);
m_makeStep->setAdditionalArguments(buildConfiguration, QStringList() << "clean");
}
// disconnect to make the changes to the items
disconnect(m_targetsList, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(itemChanged(QListWidgetItem*)));
m_buildConfiguration = buildConfiguration;
int count = m_targetsList->count();
for(int i = 0; i < count; ++i) {
QListWidgetItem *item = m_targetsList->item(i);
item->setCheckState(m_makeStep->buildsTarget(buildConfiguration, item->text()) ? Qt::Checked : Qt::Unchecked);
}
// and connect again
connect(m_targetsList, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(itemChanged(QListWidgetItem*)));
m_additionalArguments->setText(ProjectExplorer::Environment::joinArgumentList(m_makeStep->additionalArguments(m_buildConfiguration)));
}
//
// MakeStepFactory
//
bool MakeStepFactory::canCreate(const QString &name) const
{
return (Constants::MAKESTEP == name);
}
ProjectExplorer::BuildStep *MakeStepFactory::create(ProjectExplorer::Project *project, const QString &name) const
{
Q_ASSERT(name == Constants::MAKESTEP);
CMakeProject *pro = qobject_cast<CMakeProject *>(project);
Q_ASSERT(pro);
return new MakeStep(pro);
}
QStringList MakeStepFactory::canCreateForProject(ProjectExplorer::Project * /* pro */) const
{
return QStringList();
}
QString MakeStepFactory::displayNameForName(const QString & /* name */) const
{
return "Make";
}
<|endoftext|> |
Subsets and Splits
No community queries yet
The top public SQL queries from the community will appear here once available.