Compare commits
3 Commits
034bde27df
...
4629a32b69
Author | SHA1 | Date | |
---|---|---|---|
![]() |
4629a32b69 | ||
![]() |
148e235523 | ||
![]() |
a0a8004762 |
@ -12,7 +12,7 @@
|
||||
platform = espressif32
|
||||
board = esp32doit-devkit-v1
|
||||
framework = arduino
|
||||
monitor_speed = 115200
|
||||
monitor_speed = 57600
|
||||
upload-port = COM[14]
|
||||
lib_deps =
|
||||
bogde/HX711@^0.7.5
|
||||
|
20
src/config.h
20
src/config.h
@ -3,7 +3,7 @@
|
||||
// 定义公共结构,变量,硬件接口等
|
||||
///
|
||||
//
|
||||
#define VERSION "0.90" //版本
|
||||
#define VERSION "0.90" // 版本
|
||||
// 硬件接口定义////////////////////////////
|
||||
// 按钮
|
||||
#define BTN_UP 23 // 收线开关 接线:BTN_UP---GND
|
||||
@ -11,26 +11,24 @@
|
||||
#define BTN_CT 21 // 到顶检测开关
|
||||
#define BTN_TEST 18 // 测试开关
|
||||
// 称重传感器- HX711
|
||||
#define LOADCELL_DOUT_PIN 13 //16
|
||||
#define LOADCELL_SCK_PIN 33 //17
|
||||
#define LOADCELL_DOUT_PIN 13 // 16
|
||||
#define LOADCELL_SCK_PIN 33 // 17
|
||||
///////////////////////////////////////////
|
||||
#define SERVO_PIN 14 // 锁定舵机PWM控制脚
|
||||
////LED
|
||||
#define LED_DATA_PIN 25
|
||||
// Moto-CAN
|
||||
#define MOTO_CAN_RX 26
|
||||
#define MOTO_CAN_TX 27
|
||||
///serial1
|
||||
#define MOTO_CAN_RX 27
|
||||
#define MOTO_CAN_TX 26
|
||||
/// serial1
|
||||
#define SERIAL_REPORT_TX 5
|
||||
#define SERIAL_REPORT_RX 18
|
||||
/////
|
||||
#define WEIGHT_SCALE 165 // 276 //这是缩放值,根据砝码实测516.f
|
||||
#define TM_INSTORE_WEIGHT_DELAY 200 //200 // 入仓动力延时关闭时间 ms
|
||||
#define TM_INSTORE_DELAY_WEIGHT 200 // 入仓动力延时关闭时间生效的重量(g),免得空钩也延时关闭导致线拉紧 ms
|
||||
#define WEIGHT_SCALE 165 // 276 //这是缩放值,根据砝码实测516.f
|
||||
#define TM_INSTORE_WEIGHT_DELAY 200 // 200 // 入仓动力延时关闭时间 ms
|
||||
#define TM_INSTORE_DELAY_WEIGHT 200 // 入仓动力延时关闭时间生效的重量(g),免得空钩也延时关闭导致线拉紧 ms
|
||||
#define TM_INSTORE_NOWEIGHT_DELAY 50 // 空钩完全不延时也可能顶部按键按不下去,加一点延时 ms
|
||||
|
||||
|
||||
|
||||
enum HookStatus
|
||||
{
|
||||
HS_UnInit, // 还未初始化
|
||||
|
1513
src/main.cpp
1513
src/main.cpp
File diff suppressed because it is too large
Load Diff
@ -2,7 +2,7 @@
|
||||
#include <Arduino.h>
|
||||
#include <CAN.h>
|
||||
#include <ESP32SJA1000.h>
|
||||
#define MOTO_REVERSED 1 // 正反转1为正转,-1为反转
|
||||
#define MOTO_REVERSED -1 // 正反转1为正转,-1为反转
|
||||
#define MOTO_REDUCTION 36
|
||||
#define MOTO_MAXANG 8192 // 0-8191
|
||||
#define MOTO_MAXANG_HALF MOTO_MAXANG / 2
|
||||
|
@ -5,11 +5,11 @@
|
||||
#include <ESP32Servo.h>
|
||||
|
||||
#define ROPE_MAXLENGTH 700 // 最多能放700cm---实际绳子应该比这个长750之类的
|
||||
#define WHEEL_DIAMETER 3.8 // 轮子直径cm
|
||||
#define WHEEL_DIAMETER 2.3 // 轮子直径cm
|
||||
#define WHEEL_PERIMETER (WHEEL_DIAMETER * 3.1416) // 轮子周长
|
||||
#define ROPE_MAXCOUNT (ROPE_MAXLENGTH / WHEEL_PERIMETER) // 最大圈数
|
||||
|
||||
#define INSTORE_LENGTH_MIN_NONE 12.0f // 最小入仓长度,没有挂东西的情况,在最慢的速度下低于该长度也需要以SPEED_INSTORE缓慢入仓 cm -------加了软减速后必须根据速度改变!!!!
|
||||
#define INSTORE_LENGTH_MIN_NONE 12.0f // 最小入仓长度,没有挂东西的情况,在最慢的速度下低于该长度也需要以SPEED_INSTORE缓慢入仓 cm -------加了软减速后必须根据速度改变!!!!
|
||||
#define INSTORE_LENGTH_MIN_GOODS 10.0f // 最小入仓长度,有挂东西的情况 在最慢的速度下低于该长度也需要以SPEED_INSTORE缓慢入仓 cm -------加了软减速后必须根据速度改变!!!!
|
||||
|
||||
#define INSTORE_LENGTH_SPEED 0.05f // 0.0001f最小入仓长度速度平方的(输出轴速度)比例,越快越长,加了软减速后必须根据速度改变!!!!
|
||||
@ -20,8 +20,8 @@
|
||||
#define SPEED_BTN_MID 100 // 按键中等收放线速度
|
||||
#define SPEED_BTN_FAST 200 // 按键最快收放线速度
|
||||
#define SPEED_HOOK_FAST SPEED_MAX // 货物下放速度--有目标长度得情况下
|
||||
#define SPEED_HOOK_SLOW 100 // 货物快到地面速度--有目标长度得情况下
|
||||
#define SPEED_HOOK_CHECK 100 // 货物下放速度--没有目标长度得情况下能检测到脱钩的合适速度
|
||||
#define SPEED_HOOK_SLOW 100 // 货物快到地面速度--有目标长度得情况下
|
||||
#define SPEED_HOOK_CHECK 100 // 货物下放速度--没有目标长度得情况下能检测到脱钩的合适速度
|
||||
#define SPEED_HOOK_UP SPEED_MAX // 钩子回收速度
|
||||
#define SPEED_UNBLOCK 0.1 // 舵机堵转需要缓慢转的速度
|
||||
|
||||
@ -29,9 +29,9 @@
|
||||
#define TM_SERVOLOCK 300 // 舵机转到Lock和Unlock等待的时间ms
|
||||
#define TM_ACC_HS 500 // 货物快到地面减速时间--覆盖自动加减速时间--这个地方稍微长一些
|
||||
|
||||
#define SERVO_LOCKPOS 1920 // 舵机锁定位置
|
||||
#define SERVO_UNLOCKPOS 1800 // 舵机解锁位置
|
||||
#define SERVO_BLOCKUNLOCKPOS 1700 // 舵机堵转需要转回的位置--可以和SERVO_UNLOCKPOS一样,为了速度快也可以更小
|
||||
#define SERVO_LOCKPOS 1000 // 1920 // 舵机锁定位置
|
||||
#define SERVO_UNLOCKPOS 1120 // 1800 // 舵机解锁位置
|
||||
#define SERVO_BLOCKUNLOCKPOS 1100 // 舵机堵转需要转回的位置--可以和SERVO_UNLOCKPOS一样,为了速度快也可以更小
|
||||
|
||||
#define HOOK_WEIHT_MIN 100 // 最小货物重量 小于这个认为没挂东西 (克)
|
||||
|
||||
@ -55,7 +55,7 @@ typedef struct
|
||||
bool is_toplocked; // 已到顶锁住
|
||||
bool is_overweight; // 是否超重
|
||||
bool is_havegoods; // 是否有货物
|
||||
bool is_autogoodsdown; //正在自动放线中
|
||||
bool is_autogoodsdown; // 正在自动放线中
|
||||
float zero_cnt; // 0长度位置
|
||||
float speed_targe; // 当前目标速度
|
||||
MotoStatus motostatus; // 电机运行状态
|
||||
@ -111,12 +111,13 @@ private:
|
||||
void unlockservo();
|
||||
void set_hook_speed(float hooksspeed);
|
||||
void sethooksstatus(HookStatus hookstatus);
|
||||
|
||||
public:
|
||||
Motocontrol(); // 构造函数
|
||||
~Motocontrol(); // 析构函数
|
||||
void setspeed(float motospeed, float acctime = -1); // 设置速度
|
||||
void stoprun(float acctime = 0); // 停止运行
|
||||
void stopautodown(); //停止自动下放模式
|
||||
void stoprun(float acctime = 0); // 停止运行
|
||||
void stopautodown(); // 停止自动下放模式
|
||||
void setzero(); // 设置0长度位置
|
||||
int16_t getlength(); // 得到长度
|
||||
void update(); // 更新
|
||||
@ -130,7 +131,7 @@ public:
|
||||
void moto_goodsdown(float length = 0.0f); // 放下货物,自动回收
|
||||
void moto_goodsdownresume(); // 恢复自动放线
|
||||
HookStatus gethooktatus() { return _hooksstatus; } // 得到挂钩状态
|
||||
String gethooktatus_str(bool chstr=true); // 得到挂钩状态(中英文)
|
||||
String gethooktatus_str(bool chstr = true); // 得到挂钩状态(中英文)
|
||||
|
||||
void weightalign(bool weightalign); // 重量传感器是否校准--必须校准才能执行moto_hookdown
|
||||
void weightalign(bool weightalign); // 重量传感器是否校准--必须校准才能执行moto_hookdown
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user