倍福:驱动电机两种控制方式对比

驱动电机两种控制方式对比

在这里插入图片描述

验证用修改Override值控制电机转速的实际效果

规定反复启动Mc_MoveVelocity功能块为方法一,修改Override值为方法二

control_drive.cpp

#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include "myAds.hpp"
#include "myTools.hpp"

AdsTalker::Ptr adsCtrl;
AidTool::Ptr aidTool;

#define MC_Positive_Direction 1
#define MC_Negative_Direction 3;
const double rotate_reduce = 100.0;
const double drive_reduce = 50.0;
const double tire_diameter = 0.155;
const double twincat_ratio = 360.0;
const double V_MAXSPEED = 0.2;

void cmd_callback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
{
    //通过不断重新启动Mc_MOveVelocity功能块更改速度
    adsCtrl->drive_move_vel_val = (cmd_msg->linear.x / (M_PI * tire_diameter)) * rotate_reduce * twincat_ratio;
    adsCtrl->drive_move_vel_do = false;
    adsCtrl->drive_halt = false;
    cout << aidTool->toc() << " " << adsCtrl->drive_move_vel_val << " " << adsCtrl->drive_act_vel << endl; 
    if (adsCtrl->drive_move_vel_val > 0)
    {
        adsCtrl->drive_move_vel_direction = MC_Positive_Direction;
        adsCtrl->drive_move_vel_do = true;
    }
    else if (adsCtrl->drive_move_vel_val < 0)
    {
        adsCtrl->drive_move_vel_val = -adsCtrl->drive_move_vel_val;
        adsCtrl->drive_move_vel_direction = MC_Negative_Direction;
        adsCtrl->drive_move_vel_do = true;
    }
    else
    {
        adsCtrl->drive_halt = true;
        if (adsCtrl->drive_halt_over)
        {
            adsCtrl->drive_halt = false;
        }
    }

    //控制速度比率从而控制电机速度
    // adsCtrl->drive_move_vel_do = false;
    // double velocity_ratio = cmd_msg->linear.x / V_MAXSPEED;
    // if (cmd_msg->linear.x < 0)
    // {
    //     adsCtrl->drive_move_vel_direction = MC_Negative_Direction;
    //     adsCtrl->drive_move_vel_do = true;
    //     adsCtrl->drive_vel_ratio = - velocity_ratio * 100;
    // }
    // else if (cmd_msg->linear.x > 0)
    // {
    //     adsCtrl->drive_move_vel_direction = MC_Positive_Direction;
    //     adsCtrl->drive_move_vel_do = true;
    //     adsCtrl->drive_vel_ratio = velocity_ratio * 100;
    // }
    // else
    // {
    //     adsCtrl->drive_move_vel_ratio = 0.0;
    //     adsCtrl->drive_halt = true;
    //     if (adsCtrl->drive_halt_over)
    //     {
    //         adsCtrl->drive_halt = false;
    //     }
    // }
    // cout << aidTool->toc() << " " << adsCtrl->drive_move_vel_val * velocity_ratio << " " << adsCtrl->drive_act_vel << endl; 
}

int main(int argc, char *argv[])
{
    string netid = "169.254.254.142.1.1";
    string ipv4 = "169.254.254.142";
    adsCtrl = make_shared<AdsTalker>(netid, ipv4, AMSPORT_R0_PLC_TC3);
    aidTool = make_shared<AidTool>();

    if (adsCtrl->motor_enable)
    {
        cout << "Motor enabled!" << endl;
    }
    else
    {
        cout << "Motor disabled!" << endl;
        adsCtrl->motor_enable = !adsCtrl->motor_enable;
    }
    // adsCtrl->drive_move_vel_do = true;
    // adsCtrl->drive_vel_ratio = 0.0;
    // adsCtrl->drive_move_vel_val = (V_MAXSPEED / (M_PI * tire_diameter)) * rotate_reduce * twincat_ratio;

    ros::init(argc, argv, "ads_jog");
    ros::NodeHandle nh;
    aidTool->tic();
    ros::Subscriber cmd_sub = nh.subscribe("/cmd_vel", 1, cmd_callback);

    ros::spin();

    return 0;
}

在AidTool里添加了记录程序运行时间的功能,也可以用作时间戳,这里是借鉴了**A-LOAM**

#ifndef MY_TOOLS_H
#define MY_TOOLS_H

#include <stdio.h>
#include <stdlib.h>
#include <iostream>
#include <time.h>
#include <string.h>
#include <memory>
#include <chrono>

using namespace std;

class AidTool
{
private:
    chrono::time_point<chrono::system_clock> start, end;
public:
    typedef shared_ptr<AidTool> Ptr;

    AidTool(){};

    char *getNowTime(void)
    {
        time_t timer;
        struct tm *now_time;
        timer = time(NULL);
        now_time = localtime(&timer);
        return asctime(now_time);
    }

    char *getPreciseTime(void)
    {
        static char timestr[200] = {0};
        struct tm *pTempTm;
        struct timeval time;

        gettimeofday(&time, NULL);
        pTempTm = localtime(&time.tv_sec);
        if (pTempTm != NULL)
        {
            snprintf(timestr, 199, "%04d-%02d-%02d %02d:%02d:%02d.%03ld",
                     pTempTm->tm_year + 1900, pTempTm->tm_mon + 1,
                     pTempTm->tm_mday, pTempTm->tm_hour, pTempTm->tm_min,
                     pTempTm->tm_sec, time.tv_usec / 1000);
        }
        return timestr;
    }

    void tic()
    {
        start = chrono::system_clock::now();
    }

    double toc()
    {
        end = chrono::system_clock::now();
        chrono::duration<double> elapsed_seconds = end - start;
        return elapsed_seconds.count() * 1000;
    }

    ~AidTool(){};
};

#endif

记录分别在下面几个txt,02效果不太好,没有用

  • 2022-10-19-moorn01.txt(beckhoff_drive_mod1_00.csv)
  • 2022-10-19-moorn02.txt
  • 2022-10-19-moorn03.txt(beckhoff_drive_mod2_00.csv)

可以在Excel中绘制,但效果不太好,上下分别为方法一和二

在这里插入图片描述

在这里插入图片描述

所以在MATLAB里绘图,beckhoff_drivemod_comp.m

time除1000是因为log里的单位是ms,绘图时会比较大,以s为单位更合适

data1 = csvread('beckhoff_drive_mod1_00.csv',2,0);
time1 = data1(:,1) / 1000.0;
target_velocity1 = data1(:,2);
actual_velocity1 = data1(:,3);

figure(1);
plot(time1,target_velocity1,'g');
xlabel('时间/s');
ylabel('转速/度/s');
title('电机控制方式一');
grid on;
xlim([0,35]);
ylim([-15000,13000]);
set(gca,'xtick',0:2.5:35);
set(gca,'ytick',-15000:2000:13000);
hold on;
plot(time1,actual_velocity1,'r');
legend('目标转速','实际转速');
hold on;

data2 = csvread('beckhoff_drive_mod2_00.csv',2,0);
time2 = data2(:,1) / 1000.0;
target_velocity2 = data2(:,2);
actual_velocity2 = data2(:,3);

figure(2);
plot(time2,target_velocity2,'g');
xlabel('时间/s');
ylabel('转速/度/s');
title('电机控制方式二');
grid on;
xlim([0,30]);
ylim([-15000,15000]);
set(gca,'xtick',0:2.5:30);
set(gca,'ytick',-15000:2000:15000);
hold on;
plot(time2,actual_velocity2,'r');
legend('目标转速','实际转速');
hold on;

效果如下,上下分别为方法一和二

在这里插入图片描述

在这里插入图片描述

两种方法对目标速度的跟随都比较好,方法一更利于实现转向速度的补偿,因此仍采用方法一控制驱动电机

当前的独轮车控制代码,control_test.cpp

#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <mutex>
#include "myAds.hpp"
#include "myTools.hpp"

AdsTalker::Ptr adsCtrl;
AidTool::Ptr aidTool;

#define MC_Positive_Direction 1
#define MC_Negative_Direction 3;
const double rotate_reduce = 100.0;
const double drive_reduce = 50.0;
const double tire_diameter = 0.155;
const double twincat_ratio = 360.0;

mutex mut;

bool rotateHome()
{
    lock_guard<mutex> lock(mut);
    adsCtrl->home_vel = 0.05 * twincat_ratio * rotate_reduce;

    int count = 0;
    while (!adsCtrl->couple_over && count <= 10)
    {
        adsCtrl->home_run = false;
        adsCtrl->couple_do = false;
        ++count;
        adsCtrl->couple_do = true;
    }
    adsCtrl->decouple_do = false;

    adsCtrl->home_do = true;
    while (!adsCtrl->rotate_act_vel)
    {
        adsCtrl->home_run = false;
        adsCtrl->home_run = true;
        usleep(1000);
    }

    while (!adsCtrl->home_over)
    {
        cout << "Tire is homing..." << endl;
    }
    if (adsCtrl->home_over)
    {
        cout << "Tire succeeds to back home!" << endl;
        adsCtrl->home_do = false;
        return true;
    }
    mut.unlock();
    return false;
}

void cmd_callback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
{
    //判断是否为回零命令
    if (cmd_msg->linear.z == -1.0)
    {
        if (abs(adsCtrl->rotate_act_pos) > 10.0)
        {
            if (!rotateHome())
            {
                ROS_ERROR("Tire fails to back home!");
                return;
            }
        }
    }

    lock_guard<mutex> lock(mut);
    adsCtrl->ptpRel_pos = (cmd_msg->angular.z / (M_PI * 2)) * twincat_ratio * rotate_reduce;
    adsCtrl->drive_move_vel_val = (cmd_msg->linear.x / (M_PI * tire_diameter)) * rotate_reduce * twincat_ratio;
    //转向电机控制
    adsCtrl->ptpRel_do = false;
    if (adsCtrl->ptpRel_pos != 0)
    {
        adsCtrl->ptpRel_do = true;
    }
    if (adsCtrl->ptpRel_over)
    {
        adsCtrl->ptpRel_do = false;
    }

    //驱动电机控制
    adsCtrl->drive_move_vel_do = false;
    adsCtrl->drive_halt = false;
    adsCtrl->rotate_statusCheck = false;
    adsCtrl->rotate_statusCheck = true;
    if (fabs(adsCtrl->rotate_act_vel) > 60)
    {
        if (!adsCtrl->rotate_isDecelerating)
        {
            adsCtrl->drive_move_vel_val = adsCtrl->drive_move_vel_val + adsCtrl->rotate_act_vel / 2;
        }
    }
    cout << aidTool->getPreciseTime() << "  drive target velocity:" << adsCtrl->drive_move_vel_val << "; drive actual velocity:" << adsCtrl->drive_act_vel << "; rotate actual velocity:" << adsCtrl->rotate_act_vel << endl;
    if (adsCtrl->drive_move_vel_val > 0)
    {
        adsCtrl->drive_move_vel_direction = MC_Positive_Direction;
        adsCtrl->drive_move_vel_do = true;
    }
    else if (adsCtrl->drive_move_vel_val < 0)
    {
        adsCtrl->drive_move_vel_val = -adsCtrl->drive_move_vel_val;
        adsCtrl->drive_move_vel_direction = MC_Negative_Direction;
        adsCtrl->drive_move_vel_do = true;
    }
    else
    {
        adsCtrl->drive_halt = true;
        if (adsCtrl->drive_halt_over)
        {
            adsCtrl->drive_halt = false;
        }
    }
    mut.unlock();
}

int main(int argc, char *argv[])
{
    string netid = "169.254.254.142.1.1";
    string ipv4 = "169.254.254.142";
    adsCtrl = make_shared<AdsTalker>(netid, ipv4, AMSPORT_R0_PLC_TC3);
    aidTool = make_shared<AidTool>();

    if (adsCtrl->motor_enable)
    {
        cout << "Motor enabled!" << endl;
    }
    else
    {
        cout << "Motor disabled!" << endl;
        adsCtrl->motor_enable = !adsCtrl->motor_enable;
    }
    adsCtrl->ptp_vel = 0.1 * twincat_ratio * rotate_reduce;
    adsCtrl->drive_vel_ratio = 100.0;

    if (!rotateHome())
    {
        ROS_ERROR("Tire fails to back home!");
        return -1;
    }

    ros::init(argc, argv, "ads_control");
    ros::NodeHandle nh;
    ros::Subscriber cmd_sub = nh.subscribe("/cmd_vel", 1, cmd_callback);

    ros::spin();

    return 0;
}

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:/a/684321.html

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

【基础】LwM2M 通讯协议

【基础】LwM2M 通讯协议 LwM2M 协议基础LwM2M 简介LwM2M 基本架构LwM2M 资源定义 LwM2M 协议实现开源协议实现Java LwM2M Client LwM2M 协议基础 LwM2M 简介 LwM2M 的全称为 Lightweight Machine-To-Machine&#xff0c;是一种适用于物联网设备的轻量级的通讯协议&#xff0c…

再也不怕消息遗漏了,团队协作最强辅助:可道云teamOS协作通知功能,及时通知项目进展,让协作更高效

大家是否曾遇到过这样的困扰&#xff1a;在网盘中进行协作时&#xff0c;由于无法及时了解文件的最新变化&#xff0c;导致信息滞后&#xff0c;影响工作效率&#xff1f;甚至因为未能及时跟进文件更新&#xff0c;阻碍团队协作和项目推进&#xff0c;从而给团队造成严重后果。…

技巧:合并ZIP分卷压缩包

如果ZIP压缩文件文件体积过大&#xff0c;大家可能会选择“分卷压缩”来压缩ZIP文件&#xff0c;那么&#xff0c;如何合并zip分卷压缩包呢&#xff1f;今天我们分享两个ZIP分卷压缩包合并的方法给大家。 方法一&#xff1a; 我们可以将分卷压缩包&#xff0c;通过解压的方式…

C#——break、continue、goto关键字的使用

break break是搭配循环语句使用的&#xff0c;用于跳出循环。 举例 : 当for循环执行到第5次时&#xff0c;使用break方法 跳出循环。 continue continue 语句的工作原理与 break 语句类似&#xff0c;但是 continue 语句并不会跳出整个循环&#xff0c;而是跳过本次循环继续执…

idea修改国际化语言教程

教程背景 第一种&#xff0c;如果以前的项目已经有国际化语言了&#xff0c;现在的项目是导入的。 第二种&#xff0c;你中途把idea删除卸载了&#xff0c;在安装了别的版本&#xff0c;把这个项目导入进来后的。 第三种&#xff0c;你下载或复制的别人的项目。 以上这三种…

# log.info(“消息发送成功“); 红色报错 解决方案

log.info(“消息发送成功”); 红色报错 解决方案 一、错误描述&#xff1a; 在使用 idea 创建 maven 项目导入 lombok 依赖时&#xff0c;出现 log.info 报红错误&#xff0c;检查导入依赖正确&#xff0c;网络正常&#xff0c;错误依旧。 二、解决方案&#xff1a; 1、在 i…

Vue3+.NET6前后端分离式管理后台实战(二十六)

1&#xff0c;Vue3.NET6前后端分离式管理后台实战(二十六)已经在微信公众号更新&#xff0c;有兴趣的扫码关注一起交流学习。

智能家居——Kompas.ai如何改变我们的生活

引言 在现代生活中&#xff0c;智能家居逐渐成为提升生活质量的重要手段。随着科技的进步&#xff0c;智能家居的应用越来越广泛。本文将探讨智能家居的发展趋势&#xff0c;并介绍Kompas.ai如何通过AI技术改变我们的家庭生活。 智能家居的发展及其重要性 智能家居的概念起源…

现在有一个生产计划,甲乙丙3个品类共16个产品,生产时间6天,每天甲品类可以生产1张单,乙3张,丙1张,请用MySQL写出H列的效果

现在有一个生产计划&#xff0c;甲乙丙3个品类共16个产品&#xff0c;生产时间6天&#xff0c;每天甲品类可以生产1张单&#xff0c;乙3张&#xff0c;丙1张&#xff0c;请用MySQL写出H列的效果吗&#xff1f; 最终展示结果要求为&#xff1a; 品类产品生产时间开始生产时间…

IIS 服务器,下载APK 文件,用于发布更新最新的APK包

IIS 默认情况下无法下载 .apk 文件&#xff0c;需要对 IIS 服务进行设置 1、打开 IIS 对应的应用 选中MIME 类型 右键 打开功能 2、右键添加 文件扩展名&#xff1a;.apk MIME 类型输入&#xff1a;application/vnd.android.package-archive 3、重启应用 4、浏览器访问 服务地…

开发构建一个体育数据资料库:不同数据的具体意义

构建一个体育数据资料库&#xff0c;应包括“赛程赛果”、“比赛阵容”、“比赛指数”、“比赛详情”、“统计数据”以及“榜单数据”等关键信息。而借助东莞梦幻网络科技的源码&#xff0c;您可以打造一个属于自己的体育直播平台。通过该平台的资料库展示模块&#xff0c;您能…

下载centos7镜像及在VMware上安装Linux (Centos7)操作系统详细教程

文章目录 下载centos7镜像文件及在VMware上安装centos7详细教程一、下载Centos7镜像二、 利用VM安装Centos7进入VM软件安装配置虚拟机 安装Centos7进入图形化界面配置 三、访问外网 配置IP地址结语Linux配置IP网卡Linux配置本地yum源 下载centos7镜像文件及在VMware上安装cento…

Cesium开发环境搭建

由于win7搭建很费事&#xff0c;重新安装了OS&#xff0c;win10的。 记录一下&#xff0c;搭建步骤&#xff1a; 1.下载node.js。百度搜索即可下载对应的版本。下载cesium。 2.安装node.js。安装后&#xff0c;输入node -v&#xff0c;显示版本信息&#xff0c;表示安装成功…

windows下使用命令清空U盘

1、CMD命令打开后输入diskpart命令打开磁盘分区管理工具 diskpart打开如下窗口 Microsoft DiskPart 版本 10.0.19041.3636 Copyright (C) Microsoft Corporation. 在计算机上: DESKTOP-TR9HQRP 2、输入查看所有磁盘命令 list disk打印如下windows 磁盘 ###  状态    …

并查集,CF1619G - Unusual Minesweeper

一、题目 1、题目描述 2、输入输出 2.1输入 2.2输出 3、原题链接 Problem - 1619G - Codeforces 二、解题报告 1、思路分析 考虑距离在k内的两点可以合并 那么不断合并可以得到若干连通块 每个连通块自然爆炸的时间取决于连通块内的最早爆炸时间 我们还可以在每个时间点…

海外转仓系统应用案例解读:如何高效快速解决海外仓补货需求

海外仓转仓在跨境电商中是一个非常重要的业务类型&#xff0c;所谓的海外仓转仓&#xff0c;也就是指客户讲货物发送到某个海外仓后&#xff0c;根据业务需求&#xff0c;将货物中专到另一个海外仓的过程。 主要是应用在补货、销售渠道调整或者临时仓储需求上。对海外仓来说&a…

空间数据采集与管理

你还在为找不到合适的数据而苦恼吗&#xff1f;你还在面对大量数据束手无策&#xff0c;不知如何处理吗&#xff1f;对于从事生产和科研的人员来说&#xff0c;空间数据的采集与管理是地理信息系统&#xff08;GIS&#xff09;和空间分析领域的关键环节。通过准确高效地采集和管…

【Python字符串攻略】:玩转文字,编织程序的叙事艺术

文章目录 &#x1f680;一.字符串基础&#x1f308;二.查看数据类型⭐三.转化❤️四.字符串索引&#x1f6b2;五.字符串切片&#x1f3ac;六.字符串切片-步长☔七.反向切片注意事项&#x1f6b2;八.字符串&#x1f4a5;查&#x1f4a5;改&#x1f4a5;删 ❤️九.字符串拼接&…

本地Nginx的安装到使用

借鉴文章 https://blog.csdn.net/weixin_44005802/article/details/135488448 1.官网下载链接&#xff1a;链接: https://nginx.org/en/download.html 2.将下载的zip包解压后&#xff0c;打开D:…\nginx-1.20.2\conf\nginx.conf&#xff0c;修改server为实际配置。 worker_pr…

Al2O3/SiC纳米复相陶瓷力学性能显著提升 我国研究机构数量较多

Al2O3/SiC纳米复相陶瓷力学性能显著提升 我国研究机构数量较多 Al2O3/SiC纳米复相陶瓷&#xff0c;是以氧化铝&#xff08;Al2O3&#xff09;为基体相&#xff0c;以纳米碳化硅&#xff08;SiC&#xff09;为第二相&#xff0c;将第二相纳米颗粒弥散进入基体相&#xff0c;经高…