readme
parent
2c800fe5f7
commit
697e4111c6
18
README.md
18
README.md
|
@ -39,7 +39,23 @@
|
|||
#### 3 使用说明
|
||||
|
||||
1. 前往灯哥开源[FOCgit](https://gitee.com/ream_d/Deng-s-foc-controller)下载Arduino开发环境(~~也可自行下载Arduino并安装SimpleFOC~~)并打开本项目内的Arduino内的main,烧录程序到ESP32。
|
||||
2. 打开本项目内的python_gui内的FOC_gui.exe并连接上WIFI:ESP32。点击设置开始调参。
|
||||
2. 打开本项目内的`python_gui`内的`可执行文件_main`内的**main.exe**并连接上WIFI:ESP32。点击设置开始调参。
|
||||
|
||||
3. 第一次打开的话还请先输入一些初始值到eeprom中:
|
||||
|
||||
| 参数命令 | 说明 |
|
||||
| ---------------- |---------------------- |
|
||||
|TA89.3|角度|
|
||||
|SV1.8|摇摆电压|
|
||||
|SA20|摇摆角度|
|
||||
|VI120|平衡前FOC速度环的I为20|
|
||||
|VP10.5|平衡前FOC速度环的P为0.5|
|
||||
|VI210|平衡后FOC速度环的I为10|
|
||||
|VP20.2|平衡后FOC速度环的P为0.2|
|
||||
|
||||
![调参](image/tiaocan.gif)
|
||||
|
||||
4. K值可以用滑块调整,但是调整到合适值之后需要自行在Arduino的main中修改再烧录一次
|
||||
|
||||
比如让平衡角度为90度,则输入:TA90,并且会存入eeprom的位置0中 注:wifi发送**命令不能过快**,因为每次都会保存进eeprom,K参数没有保存到EEPROM所以可以使用滑条调整。
|
||||
|
||||
|
|
|
@ -1,28 +0,0 @@
|
|||
#include "Command.h"
|
||||
|
||||
void Command::run(char* str){
|
||||
for(int i=0; i < call_count; i++){
|
||||
if(isSentinel(call_ids[i],str)){ // case : call_ids = "T2" str = "T215.15"
|
||||
call_list[i](str+strlen(call_ids[i])); // get 15.15 input function
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
void Command::add(char* id, CommandCallback onCommand){
|
||||
call_list[call_count] = onCommand;
|
||||
call_ids[call_count] = id;
|
||||
call_count++;
|
||||
}
|
||||
void Command::scalar(float* value, char* user_cmd){
|
||||
*value = atof(user_cmd);
|
||||
}
|
||||
bool Command::isSentinel(char* ch,char* str)
|
||||
{
|
||||
char s[strlen(ch)+1];
|
||||
strncpy(s,str,strlen(ch));
|
||||
s[strlen(ch)] = '\0'; //strncpy need add end '\0'
|
||||
if(strcmp(ch, s) == 0)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
}
|
|
@ -1,17 +0,0 @@
|
|||
#include <Arduino.h>
|
||||
// callback function pointer definiton
|
||||
typedef void (* CommandCallback)(char*); //!< command callback function pointer
|
||||
class Command
|
||||
{
|
||||
public:
|
||||
void add(char* id , CommandCallback onCommand);
|
||||
void run(char* str);
|
||||
void scalar(float* value, char* user_cmd);
|
||||
bool isSentinel(char* ch,char* str);
|
||||
private:
|
||||
// Subscribed command callback variables
|
||||
CommandCallback call_list[20];//!< array of command callback pointers - 20 is an arbitrary number
|
||||
char* call_ids[20]; //!< added callback commands
|
||||
int call_count;//!< number callbacks that are subscribed
|
||||
|
||||
};
|
|
@ -1,93 +0,0 @@
|
|||
/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
|
||||
|
||||
This software may be distributed and modified under the terms of the GNU
|
||||
General Public License version 2 (GPL2) as published by the Free Software
|
||||
Foundation and appearing in the file GPL2.TXT included in the packaging of
|
||||
this file. Please note that GPL2 Section 2[b] requires that all works based
|
||||
on this software must also be made publicly available under the terms of
|
||||
the GPL2 ("Copyleft").
|
||||
|
||||
Contact information
|
||||
-------------------
|
||||
|
||||
Kristian Lauszus, TKJ Electronics
|
||||
Web : http://www.tkjelectronics.com
|
||||
e-mail : kristianl@tkjelectronics.com
|
||||
*/
|
||||
|
||||
#include "Kalman.h"
|
||||
|
||||
Kalman::Kalman() {
|
||||
/* We will set the variables like so, these can also be tuned by the user */
|
||||
Q_angle = 0.001f;
|
||||
Q_bias = 0.003f;
|
||||
R_measure = 0.03f;
|
||||
|
||||
angle = 0.0f; // Reset the angle
|
||||
bias = 0.0f; // Reset bias
|
||||
|
||||
P[0][0] = 0.0f; // Since we assume that the bias is 0 and we know the starting angle (use setAngle), the error covariance matrix is set like so - see: http://en.wikipedia.org/wiki/Kalman_filter#Example_application.2C_technical
|
||||
P[0][1] = 0.0f;
|
||||
P[1][0] = 0.0f;
|
||||
P[1][1] = 0.0f;
|
||||
};
|
||||
|
||||
// The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
|
||||
float Kalman::getAngle(float newAngle, float newRate, float dt) {
|
||||
// KasBot V2 - Kalman filter module - http://www.x-firm.com/?page_id=145
|
||||
// Modified by Kristian Lauszus
|
||||
// See my blog post for more information: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it
|
||||
|
||||
// Discrete Kalman filter time update equations - Time Update ("Predict")
|
||||
// Update xhat - Project the state ahead
|
||||
/* Step 1 */
|
||||
rate = newRate - bias;
|
||||
angle += dt * rate;
|
||||
|
||||
// Update estimation error covariance - Project the error covariance ahead
|
||||
/* Step 2 */
|
||||
P[0][0] += dt * (dt*P[1][1] - P[0][1] - P[1][0] + Q_angle);
|
||||
P[0][1] -= dt * P[1][1];
|
||||
P[1][0] -= dt * P[1][1];
|
||||
P[1][1] += Q_bias * dt;
|
||||
|
||||
// Discrete Kalman filter measurement update equations - Measurement Update ("Correct")
|
||||
// Calculate Kalman gain - Compute the Kalman gain
|
||||
/* Step 4 */
|
||||
float S = P[0][0] + R_measure; // Estimate error
|
||||
/* Step 5 */
|
||||
float K[2]; // Kalman gain - This is a 2x1 vector
|
||||
K[0] = P[0][0] / S;
|
||||
K[1] = P[1][0] / S;
|
||||
|
||||
// Calculate angle and bias - Update estimate with measurement zk (newAngle)
|
||||
/* Step 3 */
|
||||
float y = newAngle - angle; // Angle difference
|
||||
/* Step 6 */
|
||||
angle += K[0] * y;
|
||||
bias += K[1] * y;
|
||||
|
||||
// Calculate estimation error covariance - Update the error covariance
|
||||
/* Step 7 */
|
||||
float P00_temp = P[0][0];
|
||||
float P01_temp = P[0][1];
|
||||
|
||||
P[0][0] -= K[0] * P00_temp;
|
||||
P[0][1] -= K[0] * P01_temp;
|
||||
P[1][0] -= K[1] * P00_temp;
|
||||
P[1][1] -= K[1] * P01_temp;
|
||||
|
||||
return angle;
|
||||
};
|
||||
|
||||
void Kalman::setAngle(float angle) { this->angle = angle; }; // Used to set angle, this should be set as the starting angle
|
||||
float Kalman::getRate() { return this->rate; }; // Return the unbiased rate
|
||||
|
||||
/* These are used to tune the Kalman filter */
|
||||
void Kalman::setQangle(float Q_angle) { this->Q_angle = Q_angle; };
|
||||
void Kalman::setQbias(float Q_bias) { this->Q_bias = Q_bias; };
|
||||
void Kalman::setRmeasure(float R_measure) { this->R_measure = R_measure; };
|
||||
|
||||
float Kalman::getQangle() { return this->Q_angle; };
|
||||
float Kalman::getQbias() { return this->Q_bias; };
|
||||
float Kalman::getRmeasure() { return this->R_measure; };
|
|
@ -1,59 +0,0 @@
|
|||
/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
|
||||
|
||||
This software may be distributed and modified under the terms of the GNU
|
||||
General Public License version 2 (GPL2) as published by the Free Software
|
||||
Foundation and appearing in the file GPL2.TXT included in the packaging of
|
||||
this file. Please note that GPL2 Section 2[b] requires that all works based
|
||||
on this software must also be made publicly available under the terms of
|
||||
the GPL2 ("Copyleft").
|
||||
|
||||
Contact information
|
||||
-------------------
|
||||
|
||||
Kristian Lauszus, TKJ Electronics
|
||||
Web : http://www.tkjelectronics.com
|
||||
e-mail : kristianl@tkjelectronics.com
|
||||
*/
|
||||
|
||||
#ifndef _Kalman_h_
|
||||
#define _Kalman_h_
|
||||
|
||||
class Kalman {
|
||||
public:
|
||||
Kalman();
|
||||
|
||||
// The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
|
||||
float getAngle(float newAngle, float newRate, float dt);
|
||||
|
||||
void setAngle(float angle); // Used to set angle, this should be set as the starting angle
|
||||
float getRate(); // Return the unbiased rate
|
||||
|
||||
/* These are used to tune the Kalman filter */
|
||||
void setQangle(float Q_angle);
|
||||
/**
|
||||
* setQbias(float Q_bias)
|
||||
* Default value (0.003f) is in Kalman.cpp.
|
||||
* Raise this to follow input more closely,
|
||||
* lower this to smooth result of kalman filter.
|
||||
*/
|
||||
void setQbias(float Q_bias);
|
||||
void setRmeasure(float R_measure);
|
||||
|
||||
float getQangle();
|
||||
float getQbias();
|
||||
float getRmeasure();
|
||||
|
||||
private:
|
||||
/* Kalman filter variables */
|
||||
float Q_angle; // Process noise variance for the accelerometer
|
||||
float Q_bias; // Process noise variance for the gyro bias
|
||||
float R_measure; // Measurement noise variance - this is actually the variance of the measurement noise
|
||||
|
||||
float angle; // The angle calculated by the Kalman filter - part of the 2x1 state vector
|
||||
float bias; // The gyro bias calculated by the Kalman filter - part of the 2x1 state vector
|
||||
float rate; // Unbiased rate calculated from the rate and the calculated bias - you have to call getAngle to update the rate
|
||||
|
||||
float P[2][2]; // Error covariance matrix - This is a 2x2 matrix
|
||||
};
|
||||
|
||||
#endif
|
|
@ -1,63 +0,0 @@
|
|||
/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
|
||||
|
||||
This software may be distributed and modified under the terms of the GNU
|
||||
General Public License version 2 (GPL2) as published by the Free Software
|
||||
Foundation and appearing in the file GPL2.TXT included in the packaging of
|
||||
this file. Please note that GPL2 Section 2[b] requires that all works based
|
||||
on this software must also be made publicly available under the terms of
|
||||
the GPL2 ("Copyleft").
|
||||
|
||||
Contact information
|
||||
-------------------
|
||||
|
||||
Kristian Lauszus, TKJ Electronics
|
||||
Web : http://www.tkjelectronics.com
|
||||
e-mail : kristianl@tkjelectronics.com
|
||||
*/
|
||||
|
||||
const uint8_t IMUAddress = 0x68; // AD0 is logic low on the PCB
|
||||
const uint16_t I2C_TIMEOUT = 1000; // Used to check for errors in I2C communication
|
||||
|
||||
uint8_t i2cWrite(uint8_t registerAddress, uint8_t data, bool sendStop) {
|
||||
return i2cWrite(registerAddress, &data, 1, sendStop); // Returns 0 on success
|
||||
}
|
||||
|
||||
uint8_t i2cWrite(uint8_t registerAddress, uint8_t *data, uint8_t length, bool sendStop) {
|
||||
Wire.beginTransmission(IMUAddress);
|
||||
Wire.write(registerAddress);
|
||||
Wire.write(data, length);
|
||||
uint8_t rcode = Wire.endTransmission(sendStop); // Returns 0 on success
|
||||
if (rcode) {
|
||||
Serial.print(F("i2cWrite failed: "));
|
||||
Serial.println(rcode);
|
||||
}
|
||||
return rcode; // See: http://arduino.cc/en/Reference/WireEndTransmission
|
||||
}
|
||||
|
||||
uint8_t i2cRead(uint8_t registerAddress, uint8_t *data, uint8_t nbytes) {
|
||||
uint32_t timeOutTimer;
|
||||
Wire.beginTransmission(IMUAddress);
|
||||
Wire.write(registerAddress);
|
||||
uint8_t rcode = Wire.endTransmission(false); // Don't release the bus
|
||||
if (rcode) {
|
||||
Serial.print(F("i2cRead failed: "));
|
||||
Serial.println(rcode);
|
||||
return rcode; // See: http://arduino.cc/en/Reference/WireEndTransmission
|
||||
}
|
||||
Wire.requestFrom(IMUAddress, nbytes, (uint8_t)true); // Send a repeated start and then release the bus after reading
|
||||
for (uint8_t i = 0; i < nbytes; i++) {
|
||||
if (Wire.available())
|
||||
data[i] = Wire.read();
|
||||
else {
|
||||
timeOutTimer = micros();
|
||||
while (((micros() - timeOutTimer) < I2C_TIMEOUT) && !Wire.available());
|
||||
if (Wire.available())
|
||||
data[i] = Wire.read();
|
||||
else {
|
||||
Serial.println(F("i2cRead timeout"));
|
||||
return 5; // This error value is not already taken by endTransmission
|
||||
}
|
||||
}
|
||||
}
|
||||
return 0; // Success
|
||||
}
|
|
@ -1,124 +0,0 @@
|
|||
#include "Command.h"
|
||||
#include <Wire.h>
|
||||
#include <WiFi.h>
|
||||
#include <AsyncUDP.h> //引用以使用异步UDP
|
||||
#include "Kalman.h" // Source: https://github.com/TKJElectronics/KalmanFilter
|
||||
#include "EEPROM.h"
|
||||
Kalman kalmanZ;
|
||||
#define gyroZ_OFF 0.9
|
||||
/* ----IMU Data---- */
|
||||
|
||||
double accX, accY, accZ;
|
||||
double gyroX, gyroY, gyroZ;
|
||||
int16_t tempRaw;
|
||||
bool stable = 0;
|
||||
uint32_t last_unstable_time;
|
||||
|
||||
double gyroZangle; // Angle calculate using the gyro only
|
||||
double compAngleZ; // Calculated angle using a complementary filter
|
||||
double kalAngleZ; // Calculated angle using a Kalman filter
|
||||
|
||||
uint32_t timer;
|
||||
uint8_t i2cData[14]; // Buffer for I2C data
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
// kalman mpu6050 init
|
||||
Wire.begin(19, 18, 400000); // Set I2C frequency to 400kHz
|
||||
i2cData[0] = 7; // Set the sample rate to 1000Hz - 8kHz/(7+1) = 1000Hz
|
||||
i2cData[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling
|
||||
i2cData[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s
|
||||
i2cData[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g
|
||||
while (i2cWrite(0x19, i2cData, 4, false))
|
||||
; // Write to all four registers at once
|
||||
while (i2cWrite(0x6B, 0x01, true))
|
||||
; // PLL with X axis gyroscope reference and disable sleep mode
|
||||
|
||||
while (i2cRead(0x75, i2cData, 1))
|
||||
;
|
||||
if (i2cData[0] != 0x68)
|
||||
{ // Read "WHO_AM_I" register
|
||||
Serial.print(F("Error reading sensor"));
|
||||
while (1)
|
||||
;
|
||||
}
|
||||
|
||||
delay(100); // Wait for sensor to stabilize
|
||||
|
||||
/* Set kalman and gyro starting angle */
|
||||
while (i2cRead(0x3B, i2cData, 6))
|
||||
;
|
||||
accX = (int16_t)((i2cData[0] << 8) | i2cData[1]);
|
||||
accY = (int16_t)((i2cData[2] << 8) | i2cData[3]);
|
||||
accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]);
|
||||
double pitch = acc2rotation(accX, accY);
|
||||
|
||||
kalmanZ.setAngle(pitch);
|
||||
gyroZangle = pitch;
|
||||
|
||||
timer = micros();
|
||||
Serial.println("kalman mpu6050 init");
|
||||
}
|
||||
|
||||
void loop() {
|
||||
while (i2cRead(0x3B, i2cData, 14));
|
||||
accX = (int16_t)((i2cData[0] << 8) | i2cData[1]);
|
||||
accY = (int16_t)((i2cData[2] << 8) | i2cData[3]);
|
||||
accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]);
|
||||
tempRaw = (int16_t)((i2cData[6] << 8) | i2cData[7]);
|
||||
gyroX = (int16_t)((i2cData[8] << 8) | i2cData[9]);
|
||||
gyroY = (int16_t)((i2cData[10] << 8) | i2cData[11]);
|
||||
gyroZ = (int16_t)((i2cData[12] << 8) | i2cData[13]);
|
||||
|
||||
double dt = (double)(micros() - timer) / 1000000; // Calculate delta time
|
||||
timer = micros();
|
||||
|
||||
double pitch = acc2rotation(accX, accY);
|
||||
double gyroZrate = gyroZ / 131.0; // Convert to deg/s
|
||||
|
||||
kalAngleZ = kalmanZ.getAngle(pitch, gyroZrate + gyroZ_OFF, dt);
|
||||
gyroZangle += (gyroZrate + gyroZ_OFF) * dt;
|
||||
compAngleZ = 0.93 * (compAngleZ + (gyroZrate + gyroZ_OFF) * dt) + 0.07 * pitch;
|
||||
|
||||
// // Reset the gyro angle when it has drifted too much
|
||||
// if (gyroZangle < -180 || gyroZangle > 180)
|
||||
// gyroZangle = kalAngleZ;
|
||||
|
||||
Serial.print(pitch); Serial.print("\t");
|
||||
// Serial.print(gyroZrate); Serial.print("\t");
|
||||
// Serial.print(kalAngleZ); Serial.print("\t");
|
||||
// Serial.print(gyroZangle); Serial.print("\t");
|
||||
Serial.print(compAngleZ); Serial.print("\t");
|
||||
Serial.print("\r\n");
|
||||
}
|
||||
/* mpu6050加速度转换为角度
|
||||
acc2rotation(ax, ay)
|
||||
acc2rotation(az, ay) */
|
||||
double acc2rotation(double x, double y)
|
||||
{
|
||||
if (y < 0)
|
||||
{
|
||||
return atan(x / y) / 1.570796 * 90 + 180;
|
||||
}
|
||||
else if (x < 0)
|
||||
{
|
||||
return (atan(x / y) / 1.570796 * 90 + 360);
|
||||
}
|
||||
else
|
||||
{
|
||||
return (atan(x / y) / 1.570796 * 90);
|
||||
}
|
||||
}
|
||||
|
||||
// function constraining the angle in between -60~60
|
||||
float constrainAngle(float x)
|
||||
{
|
||||
float a = 0;
|
||||
if (x < 0)
|
||||
{
|
||||
a = 120 + x;
|
||||
if (a < abs(x))
|
||||
return a;
|
||||
}
|
||||
return x;
|
||||
}
|
Binary file not shown.
After Width: | Height: | Size: 4.7 MiB |
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1 @@
|
|||
<クdハ<>箆!ソ`。スン
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,33 @@
|
|||
#############################################################################
|
||||
##
|
||||
## Copyright (c) 2021 Riverbank Computing Limited <info@riverbankcomputing.com>
|
||||
##
|
||||
## This file is part of PyQt5.
|
||||
##
|
||||
## 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 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 do not wish to use this file under the terms of the GPL version 3.0
|
||||
## then you may purchase a commercial license. For more information contact
|
||||
## info@riverbankcomputing.com.
|
||||
##
|
||||
## This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
|
||||
## WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
|
||||
##
|
||||
#############################################################################
|
||||
|
||||
|
||||
# If pluginType is MODULE, the plugin loader will call moduleInformation. The
|
||||
# variable MODULE is inserted into the local namespace by the plugin loader.
|
||||
pluginType = MODULE
|
||||
|
||||
|
||||
# moduleInformation() must return a tuple (module, widget_list). If "module"
|
||||
# is "A" and any widget from this module is used, the code generator will write
|
||||
# "import A". If "module" is "A[.B].C", the code generator will write
|
||||
# "from A[.B] import C". Each entry in "widget_list" must be unique.
|
||||
def moduleInformation():
|
||||
return "PyQt5.QAxContainer", ("QAxWidget", )
|
|
@ -0,0 +1,33 @@
|
|||
#############################################################################
|
||||
##
|
||||
## Copyright (c) 2021 Riverbank Computing Limited <info@riverbankcomputing.com>
|
||||
##
|
||||
## This file is part of PyQt5.
|
||||
##
|
||||
## 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 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 do not wish to use this file under the terms of the GPL version 3.0
|
||||
## then you may purchase a commercial license. For more information contact
|
||||
## info@riverbankcomputing.com.
|
||||
##
|
||||
## This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
|
||||
## WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
|
||||
##
|
||||
#############################################################################
|
||||
|
||||
|
||||
# If pluginType is MODULE, the plugin loader will call moduleInformation. The
|
||||
# variable MODULE is inserted into the local namespace by the plugin loader.
|
||||
pluginType = MODULE
|
||||
|
||||
|
||||
# moduleInformation() must return a tuple (module, widget_list). If "module"
|
||||
# is "A" and any widget from this module is used, the code generator will write
|
||||
# "import A". If "module" is "A[.B].C", the code generator will write
|
||||
# "from A[.B] import C". Each entry in "widget_list" must be unique.
|
||||
def moduleInformation():
|
||||
return "PyQt5.Qsci", ("QsciScintilla", )
|
|
@ -0,0 +1,33 @@
|
|||
#############################################################################
|
||||
##
|
||||
## Copyright (c) 2021 Riverbank Computing Limited <info@riverbankcomputing.com>
|
||||
##
|
||||
## This file is part of PyQt5.
|
||||
##
|
||||
## 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 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 do not wish to use this file under the terms of the GPL version 3.0
|
||||
## then you may purchase a commercial license. For more information contact
|
||||
## info@riverbankcomputing.com.
|
||||
##
|
||||
## This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
|
||||
## WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
|
||||
##
|
||||
#############################################################################
|
||||
|
||||
|
||||
# If pluginType is MODULE, the plugin loader will call moduleInformation. The
|
||||
# variable MODULE is inserted into the local namespace by the plugin loader.
|
||||
pluginType = MODULE
|
||||
|
||||
|
||||
# moduleInformation() must return a tuple (module, widget_list). If "module"
|
||||
# is "A" and any widget from this module is used, the code generator will write
|
||||
# "import A". If "module" is "A[.B].C", the code generator will write
|
||||
# "from A[.B] import C". Each entry in "widget_list" must be unique.
|
||||
def moduleInformation():
|
||||
return 'PyQt5.QtChart', ('QtCharts.QChartView', )
|
|
@ -0,0 +1,33 @@
|
|||
#############################################################################
|
||||
##
|
||||
## Copyright (c) 2021 Riverbank Computing Limited <info@riverbankcomputing.com>
|
||||
##
|
||||
## This file is part of PyQt5.
|
||||
##
|
||||
## 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 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 do not wish to use this file under the terms of the GPL version 3.0
|
||||
## then you may purchase a commercial license. For more information contact
|
||||
## info@riverbankcomputing.com.
|
||||
##
|
||||
## This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
|
||||
## WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
|
||||
##
|
||||
#############################################################################
|
||||
|
||||
|
||||
# If pluginType is MODULE, the plugin loader will call moduleInformation. The
|
||||
# variable MODULE is inserted into the local namespace by the plugin loader.
|
||||
pluginType = MODULE
|
||||
|
||||
|
||||
# moduleInformation() must return a tuple (module, widget_list). If "module"
|
||||
# is "A" and any widget from this module is used, the code generator will write
|
||||
# "import A". If "module" is "A[.B].C", the code generator will write
|
||||
# "from A[.B] import C". Each entry in "widget_list" must be unique.
|
||||
def moduleInformation():
|
||||
return 'PyQt5.QtPrintSupport', ('QAbstractPrintDialog', 'QPageSetupDialog')
|
|
@ -0,0 +1,33 @@
|
|||
#############################################################################
|
||||
##
|
||||
## Copyright (c) 2021 Riverbank Computing Limited <info@riverbankcomputing.com>
|
||||
##
|
||||
## This file is part of PyQt5.
|
||||
##
|
||||
## 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 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 do not wish to use this file under the terms of the GPL version 3.0
|
||||
## then you may purchase a commercial license. For more information contact
|
||||
## info@riverbankcomputing.com.
|
||||
##
|
||||
## This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
|
||||
## WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
|
||||
##
|
||||
#############################################################################
|
||||
|
||||
|
||||
# If pluginType is MODULE, the plugin loader will call moduleInformation. The
|
||||
# variable MODULE is inserted into the local namespace by the plugin loader.
|
||||
pluginType = MODULE
|
||||
|
||||
|
||||
# moduleInformation() must return a tuple (module, widget_list). If "module"
|
||||
# is "A" and any widget from this module is used, the code generator will write
|
||||
# "import A". If "module" is "A[.B].C", the code generator will write
|
||||
# "from A[.B] import C". Each entry in "widget_list" must be unique.
|
||||
def moduleInformation():
|
||||
return "PyQt5.QtQuickWidgets", ("QQuickWidget", )
|
|
@ -0,0 +1,33 @@
|
|||
#############################################################################
|
||||
##
|
||||
## Copyright (c) 2021 Riverbank Computing Limited <info@riverbankcomputing.com>
|
||||
##
|
||||
## This file is part of PyQt5.
|
||||
##
|
||||
## 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 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 do not wish to use this file under the terms of the GPL version 3.0
|
||||
## then you may purchase a commercial license. For more information contact
|
||||
## info@riverbankcomputing.com.
|
||||
##
|
||||
## This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
|
||||
## WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
|
||||
##
|
||||
#############################################################################
|
||||
|
||||
|
||||
# If pluginType is MODULE, the plugin loader will call moduleInformation. The
|
||||
# variable MODULE is inserted into the local namespace by the plugin loader.
|
||||
pluginType = MODULE
|
||||
|
||||
|
||||
# moduleInformation() must return a tuple (module, widget_list). If "module"
|
||||
# is "A" and any widget from this module is used, the code generator will write
|
||||
# "import A". If "module" is "A[.B].C", the code generator will write
|
||||
# "from A[.B] import C". Each entry in "widget_list" must be unique.
|
||||
def moduleInformation():
|
||||
return "PyQt5.QtWebEngineWidgets", ("QWebEngineView", )
|
|
@ -0,0 +1,51 @@
|
|||
#############################################################################
|
||||
##
|
||||
## Copyright (C) 2014 Riverbank Computing Limited.
|
||||
## Copyright (C) 2006 Thorsten Marek.
|
||||
## All right reserved.
|
||||
##
|
||||
## This file is part of PyQt.
|
||||
##
|
||||
## You may use this file under the terms of the GPL v2 or the revised BSD
|
||||
## license as follows:
|
||||
##
|
||||
## "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 Riverbank Computing Limited 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."
|
||||
##
|
||||
#############################################################################
|
||||
|
||||
|
||||
# If pluginType is MODULE, the plugin loader will call moduleInformation. The
|
||||
# variable MODULE is inserted into the local namespace by the plugin loader.
|
||||
pluginType = MODULE
|
||||
|
||||
|
||||
# moduleInformation() must return a tuple (module, widget_list). If "module"
|
||||
# is "A" and any widget from this module is used, the code generator will write
|
||||
# "import A". If "module" is "A[.B].C", the code generator will write
|
||||
# "from A[.B] import C". Each entry in "widget_list" must be unique.
|
||||
def moduleInformation():
|
||||
return "PyQt5.QtWebKitWidgets", ("QWebView", )
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1 @@
|
|||
pip
|
|
@ -0,0 +1,18 @@
|
|||
Copyright (c) 2004 Istvan Albert unless otherwise noted.
|
||||
Copyright (c) 2006-2010 Bob Ippolito
|
||||
Copyright (2) 2010-2020 Ronald Oussoren, et. al.
|
||||
|
||||
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.
|
||||
|
||||
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.
|
|
@ -0,0 +1,289 @@
|
|||
Metadata-Version: 2.1
|
||||
Name: altgraph
|
||||
Version: 0.17.2
|
||||
Summary: Python graph (network) package
|
||||
Home-page: https://altgraph.readthedocs.io
|
||||
Author: Ronald Oussoren
|
||||
Author-email: ronaldoussoren@mac.com
|
||||
Maintainer: Ronald Oussoren
|
||||
Maintainer-email: ronaldoussoren@mac.com
|
||||
License: MIT
|
||||
Download-URL: http://pypi.python.org/pypi/altgraph
|
||||
Keywords: graph
|
||||
Platform: any
|
||||
Classifier: Intended Audience :: Developers
|
||||
Classifier: License :: OSI Approved :: MIT License
|
||||
Classifier: Programming Language :: Python
|
||||
Classifier: Programming Language :: Python :: 2
|
||||
Classifier: Programming Language :: Python :: 2.7
|
||||
Classifier: Programming Language :: Python :: 3
|
||||
Classifier: Programming Language :: Python :: 3.4
|
||||
Classifier: Programming Language :: Python :: 3.5
|
||||
Classifier: Programming Language :: Python :: 3.6
|
||||
Classifier: Programming Language :: Python :: 3.7
|
||||
Classifier: Programming Language :: Python :: 3.8
|
||||
Classifier: Programming Language :: Python :: 3.9
|
||||
Classifier: Programming Language :: Python :: 3.10
|
||||
Classifier: Topic :: Software Development :: Libraries :: Python Modules
|
||||
Classifier: Topic :: Scientific/Engineering :: Mathematics
|
||||
Classifier: Topic :: Scientific/Engineering :: Visualization
|
||||
Description-Content-Type: text/x-rst; charset=UTF-8
|
||||
License-File: LICENSE
|
||||
Project-URL: Documentation, https://altgraph.readthedocs.io/en/latest/
|
||||
Project-URL: Issue tracker, https://github.com/ronaldoussoren/altgraph/issues
|
||||
Project-URL: Repository, https://github.com/ronaldoussoren/altgraph
|
||||
|
||||
altgraph is a fork of graphlib: a graph (network) package for constructing
|
||||
graphs, BFS and DFS traversals, topological sort, shortest paths, etc. with
|
||||
graphviz output.
|
||||
|
||||
altgraph includes some additional usage of Python 2.6+ features and
|
||||
enhancements related to modulegraph and macholib.
|
||||
|
||||
CI status
|
||||
---------
|
||||
|
||||
.. image:: https://github.com/ronaldoussoren/altgraph/workflows/Lint/badge.svg
|
||||
.. image:: https://github.com/ronaldoussoren/altgraph/workflows/Test/badge.svg
|
||||
|
||||
Project links
|
||||
-------------
|
||||
|
||||
* `Documentation <https://altgraph.readthedocs.io/en/latest/>`_
|
||||
|
||||
* `Issue Tracker <https://github.com/ronaldoussoren/altgraph/issues>`_
|
||||
|
||||
* `Repository <https://github.com/ronaldoussoren/altgraph/>`_
|
||||
|
||||
|
||||
Release history
|
||||
===============
|
||||
|
||||
0.17.1
|
||||
------
|
||||
|
||||
* Explicitly mark Python 3.10 as supported in wheel metadata.
|
||||
|
||||
0.17
|
||||
----
|
||||
|
||||
* Explicitly mark Python 3.8 as supported in wheel metadata.
|
||||
|
||||
* Migrate from Bitbucket to GitHub
|
||||
|
||||
* Run black on the entire repository
|
||||
|
||||
0.16.1
|
||||
------
|
||||
|
||||
* Explicitly mark Python 3.7 as supported in wheel metadata.
|
||||
|
||||
0.16
|
||||
----
|
||||
|
||||
* Add LICENSE file
|
||||
|
||||
0.15
|
||||
----
|
||||
|
||||
* ``ObjectGraph.get_edges``, ``ObjectGraph.getEdgeData`` and ``ObjectGraph.updateEdgeData``
|
||||
accept *None* as the node to get and treat this as an alias for *self* (as other
|
||||
methods already did).
|
||||
|
||||
0.14
|
||||
----
|
||||
|
||||
- Issue #7: Remove use of ``iteritems`` in altgraph.GraphAlgo code
|
||||
|
||||
0.13
|
||||
----
|
||||
|
||||
- Issue #4: Graph._bfs_subgraph and back_bfs_subgraph return subgraphs with reversed edges
|
||||
|
||||
Fix by "pombredanne" on bitbucket.
|
||||
|
||||
|
||||
0.12
|
||||
----
|
||||
|
||||
- Added ``ObjectGraph.edgeData`` to retrieve the edge data
|
||||
from a specific edge.
|
||||
|
||||
- Added ``AltGraph.update_edge_data`` and ``ObjectGraph.updateEdgeData``
|
||||
to update the data associated with a graph edge.
|
||||
|
||||
0.11
|
||||
----
|
||||
|
||||
- Stabilize the order of elements in dot file exports,
|
||||
patch from bitbucket user 'pombredanne'.
|
||||
|
||||
- Tweak setup.py file to remove dependency on distribute (but
|
||||
keep the dependency on setuptools)
|
||||
|
||||
|
||||
0.10.2
|
||||
------
|
||||
|
||||
- There where no classifiers in the package metadata due to a bug
|
||||
in setup.py
|
||||
|
||||
0.10.1
|
||||
------
|
||||
|
||||
This is a bugfix release
|
||||
|
||||
Bug fixes:
|
||||
|
||||
- Issue #3: The source archive contains a README.txt
|
||||
while the setup file refers to ReadMe.txt.
|
||||
|
||||
This is caused by a misfeature in distutils, as a
|
||||
workaround I've renamed ReadMe.txt to README.txt
|
||||
in the source tree and setup file.
|
||||
|
||||
|
||||
0.10
|
||||
-----
|
||||
|
||||
This is a minor feature release
|
||||
|
||||
Features:
|
||||
|
||||
- Do not use "2to3" to support Python 3.
|
||||
|
||||
As a side effect of this altgraph now supports
|
||||
Python 2.6 and later, and no longer supports
|
||||
earlier releases of Python.
|
||||
|
||||
- The order of attributes in the Dot output
|
||||
is now always alphabetical.
|
||||
|
||||
With this change the output will be consistent
|
||||
between runs and Python versions.
|
||||
|
||||
0.9
|
||||
---
|
||||
|
||||
This is a minor bugfix release
|
||||
|
||||
Features:
|
||||
|
||||
- Added ``altgraph.ObjectGraph.ObjectGraph.nodes``, a method
|
||||
yielding all nodes in an object graph.
|
||||
|
||||
Bugfixes:
|
||||
|
||||
- The 0.8 release didn't work with py2app when using
|
||||
python 3.x.
|
||||
|
||||
|
||||
0.8
|
||||
-----
|
||||
|
||||
This is a minor feature release. The major new feature
|
||||
is a extensive set of unittests, which explains almost
|
||||
all other changes in this release.
|
||||
|
||||
Bugfixes:
|
||||
|
||||
- Installing failed with Python 2.5 due to using a distutils
|
||||
class that isn't available in that version of Python
|
||||
(issue #1 on the issue tracker)
|
||||
|
||||
- ``altgraph.GraphStat.degree_dist`` now actually works
|
||||
|
||||
- ``altgraph.Graph.add_edge(a, b, create_nodes=False)`` will
|
||||
no longer create the edge when one of the nodes doesn't
|
||||
exist.
|
||||
|
||||
- ``altgraph.Graph.forw_topo_sort`` failed for some sparse graphs.
|
||||
|
||||
- ``altgraph.Graph.back_topo_sort`` was completely broken in
|
||||
previous releases.
|
||||
|
||||
- ``altgraph.Graph.forw_bfs_subgraph`` now actually works.
|
||||
|
||||
- ``altgraph.Graph.back_bfs_subgraph`` now actually works.
|
||||
|
||||
- ``altgraph.Graph.iterdfs`` now returns the correct result
|
||||
when the ``forward`` argument is ``False``.
|
||||
|
||||
- ``altgraph.Graph.iterdata`` now returns the correct result
|
||||
when the ``forward`` argument is ``False``.
|
||||
|
||||
|
||||
Features:
|
||||
|
||||
- The ``altgraph.Graph`` constructor now accepts an argument
|
||||
that contains 2- and 3-tuples instead of requireing that
|
||||
all items have the same size. The (optional) argument can now
|
||||
also be any iterator.
|
||||
|
||||
- ``altgraph.Graph.Graph.add_node`` has no effect when you
|
||||
add a hidden node.
|
||||
|
||||
- The private method ``altgraph.Graph._bfs`` is no longer
|
||||
present.
|
||||
|
||||
- The private method ``altgraph.Graph._dfs`` is no longer
|
||||
present.
|
||||
|
||||
- ``altgraph.ObjectGraph`` now has a ``__contains__`` methods,
|
||||
which means you can use the ``in`` operator to check if a
|
||||
node is part of a graph.
|
||||
|
||||
- ``altgraph.GraphUtil.generate_random_graph`` will raise
|
||||
``GraphError`` instead of looping forever when it is
|
||||
impossible to create the requested graph.
|
||||
|
||||
- ``altgraph.Dot.edge_style`` raises ``GraphError`` when
|
||||
one of the nodes is not present in the graph. The method
|
||||
silently added the tail in the past, but without ensuring
|
||||
a consistent graph state.
|
||||
|
||||
- ``altgraph.Dot.save_img`` now works when the mode is
|
||||
``"neato"``.
|
||||
|
||||
0.7.2
|
||||
-----
|
||||
|
||||
This is a minor bugfix release
|
||||
|
||||
Bugfixes:
|
||||
|
||||
- distutils didn't include the documentation subtree
|
||||
|
||||
0.7.1
|
||||
-----
|
||||
|
||||
This is a minor feature release
|
||||
|
||||
Features:
|
||||
|
||||
- Documentation is now generated using `sphinx <http://pypi.python.org/pypi/sphinx>`_
|
||||
and can be viewed at <http://packages.python.org/altgraph>.
|
||||
|
||||
- The repository has moved to bitbucket
|
||||
|
||||
- ``altgraph.GraphStat.avg_hops`` is no longer present, the function had no
|
||||
implementation and no specified behaviour.
|
||||
|
||||
- the module ``altgraph.compat`` is gone, which means altgraph will no
|
||||
longer work with Python 2.3.
|
||||
|
||||
|
||||
0.7.0
|
||||
-----
|
||||
|
||||
This is a minor feature release.
|
||||
|
||||
Features:
|
||||
|
||||
- Support for Python 3
|
||||
|
||||
- It is now possible to run tests using 'python setup.py test'
|
||||
|
||||
(The actual testsuite is still very minimal though)
|
||||
|
||||
|
|
@ -0,0 +1,21 @@
|
|||
altgraph-0.17.2.dist-info/INSTALLER,sha256=zuuue4knoyJ-UwPPXg8fezS7VCrXJQrAP7zeNuwvFQg,4
|
||||
altgraph-0.17.2.dist-info/LICENSE,sha256=bBlNbbDGTUVTXRDJUUK5sM2nt9zH8d3uMCs9U289vkY,1002
|
||||
altgraph-0.17.2.dist-info/METADATA,sha256=F3Nk9zBKSMii3kNr_Ju4si34--Zoud_UMHFHsZT6yt8,7221
|
||||
altgraph-0.17.2.dist-info/RECORD,,
|
||||
altgraph-0.17.2.dist-info/WHEEL,sha256=Z-nyYpwrcSqxfdux5Mbn_DQ525iP7J2DG3JgGvOYyTQ,110
|
||||
altgraph-0.17.2.dist-info/top_level.txt,sha256=HEBeRWf5ItVPc7Y9hW7hGlrLXZjPoL4by6CAhBV_BwA,9
|
||||
altgraph-0.17.2.dist-info/zip-safe,sha256=AbpHGcgLb-kRsJGnwFEktk7uzpZOCcBY74-YBdrKVGs,1
|
||||
altgraph/Dot.py,sha256=fHS-GozpcEKyWxW2v110JaFMS68iIc0oYFlFDuNQgOQ,9901
|
||||
altgraph/Graph.py,sha256=6b6fSHLA5QSqMDnSHIO7_WJnBYIdq3K5Bt8VipRODwg,20788
|
||||
altgraph/GraphAlgo.py,sha256=Uu9aTjSKWi38iQ_e9ZrwCnzQaI1WWFDhJ6kfmu0jxAA,5645
|
||||
altgraph/GraphStat.py,sha256=vj3VqCOkzpAKggxVFLE_AlMIfPm1WN17DX4rbZjXAx4,1890
|
||||
altgraph/GraphUtil.py,sha256=1T4DJc2bJn6EIU_Ct4m0oiKlXWkXvqcXE8CGL2K9en8,3990
|
||||
altgraph/ObjectGraph.py,sha256=o7fPJtyBEgJSXAkUjzvj35B-FOY4uKzfLGqSvTitx8c,6490
|
||||
altgraph/__init__.py,sha256=YtY-rHf6X_lYk8820da2uVZT-C-B9KGpGXvBg1oZ0Fc,5015
|
||||
altgraph/__pycache__/Dot.cpython-37.pyc,,
|
||||
altgraph/__pycache__/Graph.cpython-37.pyc,,
|
||||
altgraph/__pycache__/GraphAlgo.cpython-37.pyc,,
|
||||
altgraph/__pycache__/GraphStat.cpython-37.pyc,,
|
||||
altgraph/__pycache__/GraphUtil.cpython-37.pyc,,
|
||||
altgraph/__pycache__/ObjectGraph.cpython-37.pyc,,
|
||||
altgraph/__pycache__/__init__.cpython-37.pyc,,
|
|
@ -0,0 +1,6 @@
|
|||
Wheel-Version: 1.0
|
||||
Generator: bdist_wheel (0.36.2)
|
||||
Root-Is-Purelib: true
|
||||
Tag: py2-none-any
|
||||
Tag: py3-none-any
|
||||
|
|
@ -0,0 +1 @@
|
|||
altgraph
|
|
@ -0,0 +1 @@
|
|||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue