可设置加速时间

减低测试的各种速度
---
停止时应该柔和还没修改
This commit is contained in:
pxzleo 2023-05-09 15:25:31 +08:00
parent ae901e70cc
commit 6e9a21a2c4
4 changed files with 18 additions and 11 deletions

View File

@ -57,6 +57,12 @@ void moto::update()
// moto_pid.target,dt,_ds,x,mspeed,_msoftspeed,moto_pid.output); // moto_pid.target,dt,_ds,x,mspeed,_msoftspeed,moto_pid.output);
} }
} }
void moto::settime_acc(float acctime)
{
if (acctime==-1)
_acctime=abs((_ds*SACCEL_TIME)/((float)OUTPUT_MAX*MOTO_REDUCTION)); //加减速时间
else _acctime=acctime;
}
void moto::settarget(float new_target) void moto::settarget(float new_target)
{ {
@ -81,7 +87,6 @@ void moto::settarget(float new_target)
moto_chassis.starttime=millis(); // 换算为绝对时间 moto_chassis.starttime=millis(); // 换算为绝对时间
_start_speed=moto_chassis.speed_rpm; _start_speed=moto_chassis.speed_rpm;
_ds=moto_pid.target-_start_speed; //速度差 _ds=moto_pid.target-_start_speed; //速度差
_acctime=abs((_ds*SACCEL_TIME)/((float)OUTPUT_MAX*MOTO_REDUCTION)); //加减速时间
printf("set_target:tm:%d,target:%.2f\n",moto_chassis.starttime,moto_pid.target); printf("set_target:tm:%d,target:%.2f\n",moto_chassis.starttime,moto_pid.target);
} }

View File

@ -91,6 +91,7 @@ public:
bool init(); bool init();
void update(); void update();
void settarget(float new_target); void settarget(float new_target);
void settime_acc(float acctime=-1);
moto_measure_t getmotoinfo(); moto_measure_t getmotoinfo();
void close(); void close();
}; };

View File

@ -38,9 +38,10 @@ bool Motocontrol::init(Servo *lockservo) // 初始化
return _moto_dji.init(); return _moto_dji.init();
} }
void Motocontrol::setspeed(float motospeed) // 设置速度 void Motocontrol::setspeed(float motospeed,float acctime) // 设置速度
{ {
_controlstatus.speed_targe = motospeed; _controlstatus.speed_targe = motospeed;
_moto_dji.settime_acc(acctime);
} }
void Motocontrol::setweight(int pullweight) // 设置重量 void Motocontrol::setweight(int pullweight) // 设置重量
@ -406,7 +407,7 @@ void Motocontrol::moto_goodsdown(float length)
} }
else if (length > HOOK_SLOWDOWN_LENGTH) // 长度大于慢速长度 else if (length > HOOK_SLOWDOWN_LENGTH) // 长度大于慢速长度
{ {
setspeed(SPEED_HOOK_FAST); setspeed(SPEED_HOOK_FAST,TM_ACC_HS);
moto_run(MS_Down, length - HOOK_SLOWDOWN_LENGTH); moto_run(MS_Down, length - HOOK_SLOWDOWN_LENGTH);
_hook_targetlen = HOOK_SLOWDOWN_LENGTH; _hook_targetlen = HOOK_SLOWDOWN_LENGTH;
} }

View File

@ -14,22 +14,22 @@
#define SPEED_MAX 330 //最快收放线速度--任何时候不应该超过这个速度 #define SPEED_MAX 200 //最快收放线速度--任何时候不应该超过这个速度
#define SPEED_INSTORE 5 //入仓速度,自动重量归零也是这个速度下降2cm #define SPEED_INSTORE 5 //入仓速度,自动重量归零也是这个速度下降2cm
#define SPEED_BTN_SLOW 20 //按键慢收放线速度(没有设置顶点时只能按这个速度收线) #define SPEED_BTN_SLOW 20 //按键慢收放线速度(没有设置顶点时只能按这个速度收线)
#define SPEED_BTN_MID 200 //按键中等收放线速度 #define SPEED_BTN_MID 100 //按键中等收放线速度
#define SPEED_BTN_FAST 330 //按键最快收放线速度 #define SPEED_BTN_FAST 200 //按键最快收放线速度
#define SPEED_HOOK_FAST 330 //货物下放速度--有目标长度得情况下 #define SPEED_HOOK_FAST 100 //货物下放速度--有目标长度得情况下
#define SPEED_HOOK_SLOW 20 //货物快到地面速度--有目标长度得情况下 #define SPEED_HOOK_SLOW 20 //货物快到地面速度--有目标长度得情况下
#define SPEED_HOOK_CHECK 50 //货物下放速度--没有目标长度得情况下能检测到脱钩的合适速度 #define SPEED_HOOK_CHECK 50 //货物下放速度--没有目标长度得情况下能检测到脱钩的合适速度
#define SPEED_HOOK_UP 330 //空钩上升速度 #define SPEED_HOOK_UP 100 //空钩上升速度
#define SPEED_UNBLOCK 0.1 //舵机堵转需要缓慢转的速度 #define SPEED_UNBLOCK 0.1 //舵机堵转需要缓慢转的速度
#define TM_UNBLOCK 100 //舵机堵转需要缓慢转等待的时间ms #define TM_UNBLOCK 100 //舵机堵转需要缓慢转等待的时间ms
#define TM_SERVOLOCK 200 //舵机转到Lock和Unlock等待的时间ms #define TM_SERVOLOCK 300 //舵机转到Lock和Unlock等待的时间ms
#define TM_ACC_HS 500 //货物快到地面减速时间--覆盖自动加减速时间--这个地方稍微长一些
@ -118,7 +118,7 @@ private:
public: public:
Motocontrol(); // 构造函数 Motocontrol(); // 构造函数
~Motocontrol(); // 析构函数 ~Motocontrol(); // 析构函数
void setspeed(float motospeed); // 设置速度 void setspeed(float motospeed,float acctime=-1); // 设置速度
void stop(); // 停止 void stop(); // 停止
void setzero(); // 设置0长度位置 void setzero(); // 设置0长度位置
int16_t getlength(); // 得到长度 int16_t getlength(); // 得到长度