【类 型】: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,7 +5,7 @@
|
|||||||
#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) // 最大圈数
|
||||||
|
|
||||||
@ -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 // 最小货物重量 小于这个认为没挂东西 (克)
|
||||||
|
|
||||||
@ -111,6 +111,7 @@ 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(); // 析构函数
|
||||||
|
Loading…
Reference in New Issue
Block a user