【类 型】:test
【原 因】:测试 【过 程】: 【影 响】: # 类型 包含: # feat:新功能(feature) # fix:修补bug # docs:文档(documentation) # style: 格式(不影响代码运行的变动) # refactor:重构(即不是新增功能,也不是修改bug的代码变动) # test:增加测试 # chore:构建过程或辅助工具的变动
This commit is contained in:
parent
148e235523
commit
4629a32b69
@ -2,7 +2,7 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <CAN.h>
|
#include <CAN.h>
|
||||||
#include <ESP32SJA1000.h>
|
#include <ESP32SJA1000.h>
|
||||||
#define MOTO_REVERSED 1 // 正反转1为正转,-1为反转
|
#define MOTO_REVERSED -1 // 正反转1为正转,-1为反转
|
||||||
#define MOTO_REDUCTION 36
|
#define MOTO_REDUCTION 36
|
||||||
#define MOTO_MAXANG 8192 // 0-8191
|
#define MOTO_MAXANG 8192 // 0-8191
|
||||||
#define MOTO_MAXANG_HALF MOTO_MAXANG / 2
|
#define MOTO_MAXANG_HALF MOTO_MAXANG / 2
|
||||||
|
@ -5,11 +5,11 @@
|
|||||||
#include <ESP32Servo.h>
|
#include <ESP32Servo.h>
|
||||||
|
|
||||||
#define ROPE_MAXLENGTH 700 // 最多能放700cm---实际绳子应该比这个长750之类的
|
#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 WHEEL_PERIMETER (WHEEL_DIAMETER * 3.1416) // 轮子周长
|
||||||
#define ROPE_MAXCOUNT (ROPE_MAXLENGTH / WHEEL_PERIMETER) // 最大圈数
|
#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_MIN_GOODS 10.0f // 最小入仓长度,有挂东西的情况 在最慢的速度下低于该长度也需要以SPEED_INSTORE缓慢入仓 cm -------加了软减速后必须根据速度改变!!!!
|
||||||
|
|
||||||
#define INSTORE_LENGTH_SPEED 0.05f // 0.0001f最小入仓长度速度平方的(输出轴速度)比例,越快越长,加了软减速后必须根据速度改变!!!!
|
#define INSTORE_LENGTH_SPEED 0.05f // 0.0001f最小入仓长度速度平方的(输出轴速度)比例,越快越长,加了软减速后必须根据速度改变!!!!
|
||||||
@ -20,8 +20,8 @@
|
|||||||
#define SPEED_BTN_MID 100 // 按键中等收放线速度
|
#define SPEED_BTN_MID 100 // 按键中等收放线速度
|
||||||
#define SPEED_BTN_FAST 200 // 按键最快收放线速度
|
#define SPEED_BTN_FAST 200 // 按键最快收放线速度
|
||||||
#define SPEED_HOOK_FAST SPEED_MAX // 货物下放速度--有目标长度得情况下
|
#define SPEED_HOOK_FAST SPEED_MAX // 货物下放速度--有目标长度得情况下
|
||||||
#define SPEED_HOOK_SLOW 100 // 货物快到地面速度--有目标长度得情况下
|
#define SPEED_HOOK_SLOW 100 // 货物快到地面速度--有目标长度得情况下
|
||||||
#define SPEED_HOOK_CHECK 100 // 货物下放速度--没有目标长度得情况下能检测到脱钩的合适速度
|
#define SPEED_HOOK_CHECK 100 // 货物下放速度--没有目标长度得情况下能检测到脱钩的合适速度
|
||||||
#define SPEED_HOOK_UP SPEED_MAX // 钩子回收速度
|
#define SPEED_HOOK_UP SPEED_MAX // 钩子回收速度
|
||||||
#define SPEED_UNBLOCK 0.1 // 舵机堵转需要缓慢转的速度
|
#define SPEED_UNBLOCK 0.1 // 舵机堵转需要缓慢转的速度
|
||||||
|
|
||||||
@ -29,9 +29,9 @@
|
|||||||
#define TM_SERVOLOCK 300 // 舵机转到Lock和Unlock等待的时间ms
|
#define TM_SERVOLOCK 300 // 舵机转到Lock和Unlock等待的时间ms
|
||||||
#define TM_ACC_HS 500 // 货物快到地面减速时间--覆盖自动加减速时间--这个地方稍微长一些
|
#define TM_ACC_HS 500 // 货物快到地面减速时间--覆盖自动加减速时间--这个地方稍微长一些
|
||||||
|
|
||||||
#define SERVO_LOCKPOS 1920 // 舵机锁定位置
|
#define SERVO_LOCKPOS 1000 // 1920 // 舵机锁定位置
|
||||||
#define SERVO_UNLOCKPOS 1800 // 舵机解锁位置
|
#define SERVO_UNLOCKPOS 1120 // 1800 // 舵机解锁位置
|
||||||
#define SERVO_BLOCKUNLOCKPOS 1700 // 舵机堵转需要转回的位置--可以和SERVO_UNLOCKPOS一样,为了速度快也可以更小
|
#define SERVO_BLOCKUNLOCKPOS 1100 // 舵机堵转需要转回的位置--可以和SERVO_UNLOCKPOS一样,为了速度快也可以更小
|
||||||
|
|
||||||
#define HOOK_WEIHT_MIN 100 // 最小货物重量 小于这个认为没挂东西 (克)
|
#define HOOK_WEIHT_MIN 100 // 最小货物重量 小于这个认为没挂东西 (克)
|
||||||
|
|
||||||
@ -55,7 +55,7 @@ typedef struct
|
|||||||
bool is_toplocked; // 已到顶锁住
|
bool is_toplocked; // 已到顶锁住
|
||||||
bool is_overweight; // 是否超重
|
bool is_overweight; // 是否超重
|
||||||
bool is_havegoods; // 是否有货物
|
bool is_havegoods; // 是否有货物
|
||||||
bool is_autogoodsdown; //正在自动放线中
|
bool is_autogoodsdown; // 正在自动放线中
|
||||||
float zero_cnt; // 0长度位置
|
float zero_cnt; // 0长度位置
|
||||||
float speed_targe; // 当前目标速度
|
float speed_targe; // 当前目标速度
|
||||||
MotoStatus motostatus; // 电机运行状态
|
MotoStatus motostatus; // 电机运行状态
|
||||||
@ -111,12 +111,13 @@ private:
|
|||||||
void unlockservo();
|
void unlockservo();
|
||||||
void set_hook_speed(float hooksspeed);
|
void set_hook_speed(float hooksspeed);
|
||||||
void sethooksstatus(HookStatus hookstatus);
|
void sethooksstatus(HookStatus hookstatus);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
Motocontrol(); // 构造函数
|
Motocontrol(); // 构造函数
|
||||||
~Motocontrol(); // 析构函数
|
~Motocontrol(); // 析构函数
|
||||||
void setspeed(float motospeed, float acctime = -1); // 设置速度
|
void setspeed(float motospeed, float acctime = -1); // 设置速度
|
||||||
void stoprun(float acctime = 0); // 停止运行
|
void stoprun(float acctime = 0); // 停止运行
|
||||||
void stopautodown(); //停止自动下放模式
|
void stopautodown(); // 停止自动下放模式
|
||||||
void setzero(); // 设置0长度位置
|
void setzero(); // 设置0长度位置
|
||||||
int16_t getlength(); // 得到长度
|
int16_t getlength(); // 得到长度
|
||||||
void update(); // 更新
|
void update(); // 更新
|
||||||
@ -130,7 +131,7 @@ public:
|
|||||||
void moto_goodsdown(float length = 0.0f); // 放下货物,自动回收
|
void moto_goodsdown(float length = 0.0f); // 放下货物,自动回收
|
||||||
void moto_goodsdownresume(); // 恢复自动放线
|
void moto_goodsdownresume(); // 恢复自动放线
|
||||||
HookStatus gethooktatus() { return _hooksstatus; } // 得到挂钩状态
|
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