无人机仿真XTDrone学习七:XTDrone键盘控制无人机 multirotor_keyboard_control.py程序分析四

2023-05-16

multirotor_keyboard_control.py

该程序可以通过键盘对一个或者多个无人机进行速度或者加速度的控制并更改无人机或领导者无人机飞行状态。这个脚本通过发布状态命令和速度命令话题与通讯脚本进行通讯,通讯脚本进而控制无人机飞行。
主要节点:

multirotor_type + '_multirotor_keyboard_control'
#根据传入参数进行设置。

无话题订阅

话题发布:

/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd(std_msgs/String)
/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd_vel_flu(geometry_msgs/Twist)
# 速度模式下发布状态控制与速度控制命令
/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd(std_msgs/String)
/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd_accel_flu(geometry_msgs/Twist)
# 加速度模式下发布状态控制与加速度控制命令
/xtdrone/leader/cmd(std_msgs/String)
/xtdrone/leader/cmd_vel_flu(geometry_msgs/Twist)
/xtdrone/leader/cmd_accel_flu(geometry_msgs/Twist)

# 领导者模式下发布状态控制与速度控制命令

全部代码:

import rospy
from geometry_msgs.msg import Twist
import sys, select, os
import tty, termios
from std_msgs.msg import String


MAX_LINEAR = 20
MAX_ANG_VEL = 3
LINEAR_STEP_SIZE = 0.01
ANG_VEL_STEP_SIZE = 0.01

cmd_vel_mask = False
ctrl_leader = False

msg2all = """
Control Your XTDrone!
To all drones  (press g to control the leader)
---------------------------
   1   2   3   4   5   6   7   8   9   0
        w       r    t   y        i
   a    s    d       g       j    k    l
        x       v    b   n        ,

w/x : increase/decrease forward velocity 
a/d : increase/decrease leftward velocity
i/, : increase/decrease upward velocity
j/l : increase/decrease orientation
r   : return home
t/y : arm/disarm
v/n : takeoff/land
b   : offboard
s/k : hover and remove the mask of keyboard control
0   : mask the keyboard control (for single UAV)
0~9 : extendable mission(eg.different formation configuration)
      this will mask the keyboard control
g   : control the leader
CTRL-C to quit
"""

msg2leader = """
Control Your XTDrone!
To the leader  (press g to control all drones)
---------------------------
   1   2   3   4   5   6   7   8   9   0
        w       r    t   y        i
   a    s    d       g       j    k    l
        x       v    b   n        ,

w/x : increase/decrease forward velocity
a/d : increase/decrease leftward velocity
i/, : increase/decrease upward velocity
j/l : increase/decrease orientation
r   : return home
t/y : arm/disarm
v/n : takeoff/land
b   : offboard
s/k : hover and remove the mask of keyboard control
g   : control all drones
CTRL-C to quit
"""

e = """
Communications Failed
"""

def getKey():
    tty.setraw(sys.stdin.fileno())
    rlist, _, _ = select.select([sys.stdin], [], [], 0.1)
    if rlist:
        key = sys.stdin.read(1)
    else:
        key = ''
    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
    return key

def print_msg():
    if ctrl_leader:
        print(msg2leader)
    else:
        print(msg2all)      

if __name__=="__main__":

    settings = termios.tcgetattr(sys.stdin)

    multirotor_type = sys.argv[1]
    multirotor_num = int(sys.argv[2])
    control_type = sys.argv[3]
    
    if multirotor_num == 18:
        formation_configs = ['waiting', 'cuboid', 'sphere', 'diamond']
    elif multirotor_num == 9:
        formation_configs = ['waiting', 'cube', 'pyramid', 'triangle']
    elif multirotor_num == 6:
        formation_configs = ['waiting', 'T', 'diamond', 'triangle']
    elif multirotor_num == 1:
        formation_configs = ['stop controlling']
    
    cmd= String()
    twist = Twist()   
    
    rospy.init_node(multirotor_type + '_multirotor_keyboard_control')
    
    if control_type == 'vel':
        multi_cmd_vel_flu_pub = [None]*multirotor_num
        multi_cmd_pub = [None]*multirotor_num
        for i in range(multirotor_num):
            multi_cmd_vel_flu_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd_vel_flu', Twist, queue_size=1)
            multi_cmd_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd',String,queue_size=3)
        leader_cmd_vel_flu_pub = rospy.Publisher("/xtdrone/leader/cmd_vel_flu", Twist, queue_size=1)
        leader_cmd_pub = rospy.Publisher("/xtdrone/leader/cmd", String, queue_size=1)
 
    else:
        multi_cmd_accel_flu_pub = [None]*multirotor_num
        multi_cmd_pub = [None]*multirotor_num
        for i in range(multirotor_num):
            multi_cmd_accel_flu_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd_accel_flu', Twist, queue_size=1)
            multi_cmd_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd',String,queue_size=1)
        leader_cmd_accel_flu_pub = rospy.Publisher("/xtdrone/leader/cmd_accel_flu", Twist, queue_size=1)
        leader_cmd_pub = rospy.Publisher("/xtdrone/leader/cmd", String, queue_size=3)

    forward  = 0.0
    leftward  = 0.0
    upward  = 0.0
    angular = 0.0

    print_msg()
    while(1):
        key = getKey()
        if key == 'w' :
            forward = forward + LINEAR_STEP_SIZE
            print_msg()
            if control_type == 'vel':
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            else:
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == 'x' :
            forward = forward - LINEAR_STEP_SIZE
            print_msg()
            if control_type == 'vel':
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            else:
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == 'a' :

            leftward = leftward + LINEAR_STEP_SIZE
            print_msg()
            if control_type == 'vel':
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            else:
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == 'd' :
            leftward = leftward - LINEAR_STEP_SIZE
            print_msg()
            if control_type == 'vel':
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            else:
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == 'i' :
            upward = upward + LINEAR_STEP_SIZE
            print_msg()
            if control_type == 'vel':
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            else:
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == ',' :
            upward = upward - LINEAR_STEP_SIZE
            print_msg()
            if control_type == 'vel':
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            else:
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == 'j':
            angular = angular + ANG_VEL_STEP_SIZE
            print_msg()
            print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == 'l':
            angular = angular - ANG_VEL_STEP_SIZE
            print_msg()
            print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

        elif key == 'r':
            cmd = 'AUTO.RTL'
            print_msg()
            print('Returning home')
        elif key == 't':
            cmd = 'ARM'
            print_msg()
            print('Arming')
        elif key == 'y':
            cmd = 'DISARM'
            print_msg()
            print('Disarming')
        elif key == 'v':
            cmd = 'AUTO.TAKEOFF'
            cmd = ''
            print_msg()
            #print('Takeoff mode is disenabled now')
        elif key == 'b':
            cmd = 'OFFBOARD'
            print_msg()
            print('Offboard')
        elif key == 'n':
            cmd = 'AUTO.LAND'
            print_msg()
            print('Landing')
        elif key == 'g':
            ctrl_leader = not ctrl_leader
            print_msg()
        elif key in ['k', 's']:
            cmd_vel_mask = False
            forward   = 0.0
            leftward   = 0.0
            upward   = 0.0
            angular  = 0.0
            cmd = 'HOVER'
            print_msg()
            print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            print('Hover')
        else:
            for i in range(10):
                if key == str(i):
                    cmd = formation_configs[i]
                    print_msg()
                    print(cmd)
                    cmd_vel_mask = True
            if (key == '\x03'):
                break

        if forward > MAX_LINEAR:
            forward = MAX_LINEAR
        elif forward < -MAX_LINEAR:
            forward = -MAX_LINEAR
        if leftward > MAX_LINEAR:
            leftward = MAX_LINEAR
        elif leftward < -MAX_LINEAR:
            leftward = -MAX_LINEAR
        if upward > MAX_LINEAR:
            upward = MAX_LINEAR
        elif upward < -MAX_LINEAR:
            upward = -MAX_LINEAR
        if angular > MAX_ANG_VEL:
            angular = MAX_ANG_VEL
        elif angular < -MAX_ANG_VEL:
            angular = - MAX_ANG_VEL
            
        twist.linear.x = forward; twist.linear.y = leftward ; twist.linear.z = upward
        twist.angular.x = 0.0; twist.angular.y = 0.0;  twist.angular.z = angular

        for i in range(multirotor_num):
            if ctrl_leader:
                if control_type == 'vel':
                    leader_cmd_vel_flu_pub.publish(twist)
                else:
                    leader_cmd_accel_flu_pub.publish(twist)
                leader_cmd_pub.publish(cmd)
            else:
                if not cmd_vel_mask:
                    if control_type == 'vel':
                        multi_cmd_vel_flu_pub[i].publish(twist)   
                    else:
                        multi_cmd_accel_flu_pub[i].publish(twist)
                multi_cmd_pub[i].publish(cmd)
                
        cmd = ''

    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)

库函数

import rospy
from geometry_msgs.msg import Twist # 速度or加速度话题消息类型
import sys, select, os
import tty, termios
from std_msgs.msg import String # 状态控制话题消息类型

定义变量

MAX_LINEAR = 20 # 最大线速度
MAX_ANG_VEL = 3 # 最大角速度
LINEAR_STEP_SIZE = 0.01 # 每次按键改变的步长
ANG_VEL_STEP_SIZE = 0.01

cmd_vel_mask = False # 速度控制掩码为False时可以控制速度,为True时不能控制速度
ctrl_leader = False # 领导者模式

msg2all = """
Control Your XTDrone!
To all drones  (press g to control the leader)
---------------------------
   1   2   3   4   5   6   7   8   9   0
        w       r    t   y        i
   a    s    d       g       j    k    l
        x       v    b   n        ,

w/x : increase/decrease forward velocity 
a/d : increase/decrease leftward velocity
i/, : increase/decrease upward velocity
j/l : increase/decrease orientation
r   : return home
t/y : arm/disarm
v/n : takeoff/land
b   : offboard
s/k : hover and remove the mask of keyboard control
0   : mask the keyboard control (for single UAV)
0~9 : extendable mission(eg.different formation configuration)
      this will mask the keyboard control
g   : control the leader
CTRL-C to quit
"""
 # 单机控制模式打印字符串
msg2leader = """
Control Your XTDrone!
To the leader  (press g to control all drones)
---------------------------
   1   2   3   4   5   6   7   8   9   0
        w       r    t   y        i
   a    s    d       g       j    k    l
        x       v    b   n        ,

w/x : increase/decrease forward velocity
a/d : increase/decrease leftward velocity
i/, : increase/decrease upward velocity
j/l : increase/decrease orientation
r   : return home
t/y : arm/disarm
v/n : takeoff/land
b   : offboard
s/k : hover and remove the mask of keyboard control
g   : control all drones
CTRL-C to quit
"""
# 领导者控制模式打印字符串
e = """
Communications Failed
"""
# 通讯失败打印字符串

用到的子程序定义

def getKey():
    tty.setraw(sys.stdin.fileno())
    rlist, _, _ = select.select([sys.stdin], [], [], 0.1)
    if rlist:
        key = sys.stdin.read(1)
    else:
        key = ''
    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
    return key
# 获取键盘在终端的按键程序
def print_msg():
    if ctrl_leader:
        print(msg2leader)
    else:
        print(msg2all)      
# 打印说明字符串

主函数

变量声明与定义

# 将传入的参数赋值 
	multirotor_type = sys.argv[1] # 无人机类型
    multirotor_num = int(sys.argv[2]) # 无人机数量
    control_type = sys.argv[3] # 控制方式-速度控制or加速度控制
    # 多机时的编队形状配置
    if multirotor_num == 18:
        formation_configs = ['waiting', 'cuboid', 'sphere', 'diamond']
    elif multirotor_num == 9:
        formation_configs = ['waiting', 'cube', 'pyramid', 'triangle']
    elif multirotor_num == 6:
        formation_configs = ['waiting', 'T', 'diamond', 'triangle']
    elif multirotor_num == 1:
        formation_configs = ['stop controlling']
    
    cmd= String()
    twist = Twist()   

启动ROS节点并设置发布话题,如果为多机则for循环设置每个无人机对应的控制话题。

rospy.init_node(multirotor_type + '_multirotor_keyboard_control')
    
    if control_type == 'vel':
        multi_cmd_vel_flu_pub = [None]*multirotor_num # 设置数组
        multi_cmd_pub = [None]*multirotor_num
        for i in range(multirotor_num):
            multi_cmd_vel_flu_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd_vel_flu', Twist, queue_size=1)
            multi_cmd_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd',String,queue_size=3)
        leader_cmd_vel_flu_pub = rospy.Publisher("/xtdrone/leader/cmd_vel_flu", Twist, queue_size=1)
        leader_cmd_pub = rospy.Publisher("/xtdrone/leader/cmd", String, queue_size=1)
 
    else:
        multi_cmd_accel_flu_pub = [None]*multirotor_num
        multi_cmd_pub = [None]*multirotor_num
        for i in range(multirotor_num):
            multi_cmd_accel_flu_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd_accel_flu', Twist, queue_size=1)
            multi_cmd_pub[i] = rospy.Publisher('/xtdrone/'+multirotor_type+'_'+str(i)+'/cmd',String,queue_size=1)
        leader_cmd_accel_flu_pub = rospy.Publisher("/xtdrone/leader/cmd_accel_flu", Twist, queue_size=1)
        leader_cmd_pub = rospy.Publisher("/xtdrone/leader/cmd", String, queue_size=3)

while循环程序

程序思路就是获取键盘按键设置forward,leftward,upward,angular四个变量和控制状态变量cmd。由于大多重复,下面举例说明。

if key == 'w' :
            forward = forward + LINEAR_STEP_SIZE
            print_msg()
            if control_type == 'vel':
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))
            else:
                print("currently:\t forward vel %.2f\t leftward vel %.2f\t upward vel %.2f\t angular %.2f " % (forward, leftward, upward, angular))

这段代码指当键盘输入w时forward变量加一个步长,并且打印信息。

elif key == 't':
   cmd = 'ARM'
   print_msg()
   print('Arming')

这段代码指当键盘输入t时cmd变量设置为ARM并打印信息。

if forward > MAX_LINEAR:
   forward = MAX_LINEAR
elif forward < -MAX_LINEAR:
   forward = -MAX_LINEAR

限制变量的大小。

twist.linear.x = forward; twist.linear.y = leftward ; twist.linear.z = upward
twist.angular.x = 0.0; twist.angular.y = 0.0;  twist.angular.z = angular

        for i in range(multirotor_num):
            if ctrl_leader:
                if control_type == 'vel':
                    leader_cmd_vel_flu_pub.publish(twist)
                else:
                    leader_cmd_accel_flu_pub.publish(twist)
                leader_cmd_pub.publish(cmd)
            else:
                if not cmd_vel_mask: # 判断速度控制掩码,掩码为False则发布速度控制话题
                    if control_type == 'vel':
                        multi_cmd_vel_flu_pub[i].publish(twist)   
                    else:
                        multi_cmd_accel_flu_pub[i].publish(twist)
                multi_cmd_pub[i].publish(cmd)

最终发布速度与状态话题,实现对无人机的控制。由于编队控制时启用其他速度控制脚本,所以此脚本在编队运行时只发布队形控制命令不发布控制速度话题。

参考资料
程序源码

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

无人机仿真XTDrone学习七:XTDrone键盘控制无人机 multirotor_keyboard_control.py程序分析四 的相关文章

  • 基于STM32的FreeRTOS学习之任务基础知识(六)

    记录一下 xff0c 方便以后翻阅 RTOS系统的核心是任务管理 xff0c 初学RTOS系统必须先掌握任务的创建 删除 挂起和恢复等操作 1 什么是多任务系统 玩裸机一般都是在main函数里用while 1 做一个死循环完成所有处理 xf
  • git 推送出现 “fatal: The remote end hung up unexpectedly“ 解决方案

    https blog csdn net qq 41241767 article details 98181952 git 推送出现 34 fatal The remote end hung up unexpectedly 34 解决方案 h
  • 操作系统的设计指导思想——主奴机制

    在学习操作系统的过程中我们会发现一个问题 xff1a 应用程序是应用程序 xff0c 操作系统也是程序 xff0c 操作系统程序凭什么能对应用程序进行组织 管理和协调而不受应用程序损害呢 xff1f 我们认为凭的是特权机制 要想让操作系统做
  • VScode如何配置Git

    注意 xff1a 食用本篇博客的前提是你已经安装好了Git xff0c 并且也有一定的Git基础 因为有些git中比较常用的功能我会略过 第一步 xff1a 配置Git环境变量 右键 我的电脑 xff0c 选择 属性 xff0c 在弹出的对
  • FMC/FSMC/EXMC总线NORFlash/PSRAM接口(异步-复用-不突发/同步-复用-突发)

    请勿转载 目录 1 简介 1 1 框图 1 2 接口定义 1 3 读写时序图 时序配置参数 1 4 PSRAM控制器异步工作模式分类 1 5 PSRAM寄存器配置 1 5 1 控制寄存器BCR 1 5 2 片选时序寄存器BTR 1 5 3
  • 开平方_复数有效值+角度的verilog代码

    1 逐位比较法 二进制 FPGA篇 xff08 一 xff09 基于verilog的定点开方运算 1 逐次逼近算法 该篇文章中有详细描述 假设被开方数rad i 7 0 xff0c 则结果qout 3 0 位宽为4位 xff0c 从最高位到
  • GOOSE报文分析_详解GOOSE服务

    https www cnblogs com software4y p 10017602 html http blog sina com cn s blog af8298410102wnvm html https www cnblogs co
  • 循环冗余校验(CRC)之verilog实现

    有一个网站在这一方面做的特别好 xff0c 直接生成代码 链接 xff1a http www easics com webtools crctool 循环冗余校验 xff0c 也称为CRC检验 xff0c 这是一个很常见的 xff0c 很成
  • 从原理上解释什么是DDR的ZQ校准?

    前言 首先我们我们看下下图的电路 xff0c 在DDR的电路中通常有ZQ部分的电路 xff0c 外接1 高精度的240ohm电阻 xff0c 那么这个240ohm电阻究竟是做什么用的呢 xff1f 很多做了硬件或者驱动开发很多年的工程师仍然
  • 串行数据异步动态相位采样处理iodelay-iserdes应用+CDR数据恢复方案

    目录 一 用iserdes的LVDS视频接口 二 LVDS 4倍异步过采样 ISERDES2 三 8倍过采样 CDR数据恢复 Select IO 替代 RocketIO 典型应用SD SDI 四 4倍过采样 CDR数据恢复 一 用iserd
  • 接收灵敏度dbm与W

    一 基本概念 xff1a 接收灵敏度 官方概念 xff1a 接收机能够识别到的 最低的电磁波能量 单位也是dBm 解读 xff1a 接收灵敏度 xff0c 就是你的耳朵能听到的最小的声音 耳朵灵敏度高的 xff0c 能够听到很远的声音 例如
  • 三段式过流保护、差动保护

    1 基本原理 供电系统中的线路 设备等故障 xff0c 会产生短路电流 短路电流比线路正常工作时大很多 通过电流互感器测量这个电流值 xff0c 和电流值的持续时间 xff0c 达到整定值时输出跳闸信号 xff0c 这个就是过电流保护的基本
  • Unexpandable Clocks不可扩展时钟 UG903

    同源时钟可能同步 xff0c 可能异步 xff1f 同源时钟由同一个PLL MMCM产生 xff0c 相位固定 xff0c 能否产生小数倍关系 xff1f 不可扩展时钟能否归类到异步时钟 xff1f 不可扩展时钟是指时钟引擎无法在1000个
  • allegro 尺寸标注操作未到板边的处理

    1 进入尺寸标注 2 右击选择线性 xff0c parameters中可以改参数 xff0c 默认即可 3 打开尺寸层 xff0c 点击板边框 如果有圆弧没有标注到板边 xff0c 可以在右侧find中关闭其它项 xff0c 点击两个板边标
  • 安装boost

    安装boost 从官网下载并解压到适当位置 Boost网站 在解压后的目录中找到 bootstrap bat点击运行 xff0c 并等待结束 这时会出现b2 exe文件 xff0c 点击运行 xff0c 耐心等待结束 xff08 安装后产生
  • 基于PCIe的NVMe协议在FPGA中实现方法

    NVMe协议是工作在PCIE的最上层协议层的 xff0c 故需要先搞清楚PCIE 本文基于Xilinx的UltraScale 43 xff0c 开发工具为Vivado2021 2 学习中以spec为主 xff0c 其它资料辅助参考 重点介绍
  • PX4地面参数配置

    1 空速计 在不使用空速计的情况下 xff0c 配置CBRK AIRSPD CHK参数失能传感器 xff0c waining消失 2 数传部分 配置SER TEL1 BAUD的波特率与数传一致 xff0c 在地面站选择数传端口进行连接 xf
  • 企业微信公众账号自定义应用模块中撤回历史消息的方法

    企业微信 xff0c 公众账号自定义应用模块中撤回历史消息的方法 注意 xff1a 此方法适用于撤回超过24小时的历史消息 下载这个工具 xff1a postman xff1a http www downza cn soft 205171
  • windows的BAT或者linux的VI下批量更改替换文件名的脚本

    windows 的BAT 或者linux 的VI 下批量更改替换文件名的脚本 本来离开写脚本有些日子了 xff0c 倒是现在有些文件处理或者EXCEL 工作簿要处理的话 xff0c 还是会用简化流程来处理 脚本函数则帮我解决了很多麻烦事 昨
  • 那些年,我们一起读过的《JAVA与模式》

    那些年 xff0c 我们一起读过的 JAVA与模式 刚上大二 xff0c 买回来那一本厚厚的 JAVA与模式 时 xff0c 我还很不舍得 xff0c 这价格 xff0c 可以供一周的生活费了 既然买了 xff0c 就得读一读吧 先说说阎宏

随机推荐