WO2021017356A1 - 一种双足机器人步态生成与优化方法 - Google Patents

一种双足机器人步态生成与优化方法 Download PDF

Info

Publication number
WO2021017356A1
WO2021017356A1 PCT/CN2019/123181 CN2019123181W WO2021017356A1 WO 2021017356 A1 WO2021017356 A1 WO 2021017356A1 CN 2019123181 W CN2019123181 W CN 2019123181W WO 2021017356 A1 WO2021017356 A1 WO 2021017356A1
Authority
WO
WIPO (PCT)
Prior art keywords
state
biped robot
gait
robot
biped
Prior art date
Application number
PCT/CN2019/123181
Other languages
English (en)
French (fr)
Inventor
黄强
陈学超
余张国
韩连强
廖文希
罗舟
Original Assignee
北京理工大学
Priority date (The priority date is an assumption and is not a legal conclusion. Google has not performed a legal analysis and makes no representation as to the accuracy of the date listed.)
Filing date
Publication date
Application filed by 北京理工大学 filed Critical 北京理工大学
Publication of WO2021017356A1 publication Critical patent/WO2021017356A1/zh

Links

Images

Classifications

    • BPERFORMING OPERATIONS; TRANSPORTING
    • B25HAND TOOLS; PORTABLE POWER-DRIVEN TOOLS; MANIPULATORS
    • B25JMANIPULATORS; CHAMBERS PROVIDED WITH MANIPULATION DEVICES
    • B25J9/00Programme-controlled manipulators
    • B25J9/16Programme controls
    • B25J9/1628Programme controls characterised by the control loop
    • B25J9/1633Programme controls characterised by the control loop compliant, force, torque control, e.g. combined with position control
    • BPERFORMING OPERATIONS; TRANSPORTING
    • B25HAND TOOLS; PORTABLE POWER-DRIVEN TOOLS; MANIPULATORS
    • B25JMANIPULATORS; CHAMBERS PROVIDED WITH MANIPULATION DEVICES
    • B25J9/00Programme-controlled manipulators
    • B25J9/16Programme controls
    • B25J9/1656Programme controls characterised by programming, planning systems for manipulators
    • B25J9/1664Programme controls characterised by programming, planning systems for manipulators characterised by motion, path, trajectory planning
    • BPERFORMING OPERATIONS; TRANSPORTING
    • B62LAND VEHICLES FOR TRAVELLING OTHERWISE THAN ON RAILS
    • B62DMOTOR VEHICLES; TRAILERS
    • B62D57/00Vehicles characterised by having other propulsion or other ground- engaging means than wheels or endless track, alone or in addition to wheels or endless track
    • B62D57/02Vehicles characterised by having other propulsion or other ground- engaging means than wheels or endless track, alone or in addition to wheels or endless track with ground-engaging propulsion means, e.g. walking members
    • B62D57/032Vehicles characterised by having other propulsion or other ground- engaging means than wheels or endless track, alone or in addition to wheels or endless track with ground-engaging propulsion means, e.g. walking members with alternately or sequentially lifted supporting base and legs; with alternately or sequentially lifted feet or skid

Definitions

  • the invention belongs to the technical field of humanoid robots, and specifically relates to a method for generating and optimizing the gait of a biped robot.
  • the biped robot has the characteristics of human appearance. It adopts biped walking and two-handed operation. It is easy to adapt to the human working environment and use human tools. It has important applications in the aging society, family services, public safety and other dangerous environment operations, national defense and other fields. demand. Although biped robots have achieved landmark results in motion planning, balance control, operation, and system integration in a structured environment, compared with the wide application of industrial robots in industrial production, biped robots are far from practical applications. Big gap.
  • the walking gait of the biped robot directly affects the walking performance of the robot. Different gaits have different characteristics such as stability, energy efficiency, and degree of anthropomorphism. Therefore, it is very important to design a reasonable walking gait. Humans have different walking gaits to adapt to different walking environments.
  • an omnidirectional coupling of oscillating neuron units is proposed to generate foot and center of mass trajectories, and sensors are used to detect environmental information to form a feedback loop to obtain gait trajectories; in addition, there is a spherical hinge dual degree of freedom thumb root joint device that uses Dual motors are connected with threads, ball hinges and herringbone linkage mechanism, etc., which comprehensively realize the independent swing and fitting action of the root of the thumb; others have proposed a five-finger dexterous hand finger side swing and palm-pointing mechanism based on a screw linkage mechanism , Use the screw nut and connecting rod system to realize the movement of the finger base joint with two degrees of freedom.
  • the placement position of the motor is restricted by the driven object, which occupies a large amount of palm space, increases the weight of the hand, reduces flexibility, and requires high precision in coordination with installation, and does not have the versatility of the driving method.
  • a biped robot gait generation and optimization method is proposed, with the purpose of providing a biped robot gait generation method with higher universality.
  • a biped robot gait generation and optimization method In the finite state machine, the biped robot's gait database is constructed according to the target pose of the biped robot's state; the conditions for switching between the states of the triggering robot are set; During each state switching process, the motion trajectory of the supporting leg is planned by the joint cubic interpolation method, and the motion trajectory of the swinging leg is optimized by the Gaussian pseudo-spectrum method; finally, the finite state machine generates a variety of different motion modes of the biped robot gait.
  • the switching conditions include man-made triggers, time triggers, and event triggers.
  • the time trigger is the duration between the set states
  • the event trigger is whether the swing leg of the robot touches the ground.
  • the state of the biped robot includes: the initial state of the robot standing on the ground with both feet, the state that only the right foot is supported, the state that the left foot touches the ground, the state that the left foot supports, the state that the right foot touches the ground, and the airborne state. status.
  • the process of the joint cubic interpolation method is: according to the target angle ⁇ 1 , ⁇ 2 of the front and rear states, and the angular velocity of the front and rear states
  • the duration between and the state is T, when the current state duration is t, the current reference angle ⁇ and angular velocity after cubic interpolation for:
  • the method for optimizing the motion trajectory of the swinging leg by the Gaussian pseudospectral method is:
  • M is the inertia matrix of the joint space
  • C is the resultant force vector of Coriolis force, centrifugal force and gravity
  • q sw is the angle between the hip joint and the knee joint of the swing leg
  • Is the angular velocity of the hip joint and the knee joint of the swing leg
  • ⁇ sw is the driving torque
  • S3 establish an evaluation function: Among them, x e is the state at the last moment, and S, Q, and R are weight matrices;
  • x(T) is the real state time history
  • X(T) is the state time history approximated by the Lagrangian interpolation polynomial
  • t 0 is the start time
  • t f is the end time
  • X 0 is the state time history at t 0
  • X f is the state time history at t f
  • w k is the Gaussian integral weight
  • g is The piecewise integral function is the integral of the dynamic equation
  • T k is the Gauss point
  • X k X(T k )
  • k 0,1,...,N;
  • the position of the end of the foot of the swinging leg is restricted, and the position of the end of the foot of the swinging leg in the vertical direction should be greater than 0;
  • the present invention provides a method for generating and optimizing the gait of a biped robot, which does not simplify the biped robot to avoid errors caused by the inaccuracy of the model, thereby increasing the difficulty of control; using the finiteness and symmetry of the finite state machine to plan dual
  • the operation of the foot robot simplifies the planning process, and adopts the whole-body dynamics constraint to reduce the energy loss during the operation of the biped robot; because there is no ZMP restriction, this method can be used on either a footbed or a point-footed biped robot. Applicability improves the universality of the method.
  • Figure 1 is a flow chart of the method for generating and optimizing the gait of the biped robot of the present invention
  • Figure 2 is a schematic diagram of different states of the biped robot during walking
  • Figure 3 is a schematic diagram of the motion state of the biped robot in different modes.
  • FIG. 1 A biped robot gait generation and optimization method is shown in Figure 1:
  • the biped robot divides the robot states into 6 types according to the different supporting legs during walking. They are the initial state of the robot standing on the ground with both feet, the state where only the right foot is supported, and the left foot touching The state of the ground 2, the state of the left foot support 3, the state of the right foot touching the ground 4, and the empty state, the joint target angle and walking reference speed are set through the human walking state information; in the finite state machine, according to the different states of the biped robot Construct the gait library of the biped robot with the target pose.
  • the switching conditions include human trigger, time trigger and event trigger.
  • the event trigger is specifically whether the robot’s swing leg touches the ground; as shown in Figure 2, when a human input control command After that, the robot starts to move from the initial state, that is, using human touch; after a period of time, it reaches state 1, and the robot starts to enter the cycle of walking cycle.
  • the cycle walking phase there are 2 switching conditions for switching between the 4 states.
  • time triggering that is, setting whether the current state continues to run for 0.2s
  • event triggering that is, the robot swings its legs.
  • the switching rule is: when state 1 is switched to state 2, and state 3 is switched to state 4, the condition is whether the current state continues to run for 0.2s, when state 2 is switched to state 3, and state 4 is switched to state 1.
  • the condition is whether the swinging leg of the robot touches the ground; Figure 2 shows that the gait of the robot is symmetrically distributed, which is consistent with the rhythmic periodic motion of human walking. If the robot is in the airborne state during walking, when the robot is in the airborne state, the robot will keep the posture of the whole body unchanged and wait for the robot to land. When it detects that both feet touch the ground, it will switch to state 1.
  • each state in the gait library only represents the pose at the initial moment of the current state of the robot, when switching between the two states, the reference joint trajectory will jump, causing the robot to run free when executing the planned trajectory. Stable phenomenon), so it is necessary to obtain a smooth trajectory through an interpolation function between the two state target angles. Because the angle of the supporting leg changes little and plays a supporting role, only the cubic interpolation function is used for simple trajectory planning; for the swing leg due to the large motion range, it plays an important role in the balance and stability of the robot, so Gaussian pseudo-spectrum is used Method of optimization method for interpolation planning. Finally, the finite state machine generates the gait of the biped robot with multiple different motion modes. The specific process is as follows:
  • the target angle and angular velocity of the two states are ⁇ 1 , ⁇ 2 and The duration between states is T, when the current state duration is t, the current reference angle ⁇ and angular velocity after three interpolations for:
  • a 0 ,a 1 ,a 2 ,a 3 ,s are only process variables in the calculation, and have no practical meaning;
  • M ⁇ R 2 ⁇ 2 is the inertia matrix of the joint space
  • C ⁇ R 2 ⁇ 1 is the resultant force vector of Coriolis force, centrifugal force and gravity, They are the angle of the hip and knee joints of the swinging leg, the angular velocity of the hip and knee joints of the swinging leg, and the driving torque of the hip and knee joints of the swinging leg.
  • Is the angle of the hip joint of the swing leg Is the angle of the knee joint of the swing leg, Is the angular velocity of the hip joint of the swing leg, Is the angular velocity of the knee joint of the swing leg, Is the driving torque of the hip joint of the swing leg, It is the driving torque of the knee joint of the swing leg.
  • the dynamic equation of the swing leg must be deformed to meet the requirements of the optimization algorithm. Establish a nonlinear state equation:
  • the angular acceleration can be expressed as:
  • x e is the state at the last moment
  • S, Q, and R are the weight matrices
  • t is the time.
  • t 0 is the start time
  • t f is the end time
  • x(T) is the real state time history
  • X(T) is the state time history approximated by Lagrange interpolation polynomial
  • w k is the Gaussian integral weight.
  • the position of the end of the foot of the swinging leg needs to be restricted, that is, the position of the end of the foot of the swinging leg in the vertical direction should be greater than 0 .
  • the Gaussian pseudospectral method needs to meet the set whole-body dynamics constraint conditions to optimize the motion trajectory of the swinging leg.
  • the method to construct the robot's whole-body dynamics equation is:
  • D, N, G, B, J are the matrices related to inertia, Coriolis force, gravity, moment transformation and Jacobian respectively
  • F E is the external force on the end of the swinging leg
  • the simulation experiment proves that the method can generate the gait of the biped robot with many different motion modes from the finite state machine. As shown in Figure 3, a variety of different modes of movement can be formed, including slow walking, fast walking, jumping forward and so on.
  • the present invention uses the state machine to generate the motion mode of different robots, which simplifies the planning process and
  • the use of whole-body dynamics constraints reduces the energy loss during the operation of the biped robot; because there is no ZMP limitation, the method can be applied to biped robots with footbed or point feet, which improves the universality of the method .

Landscapes

  • Engineering & Computer Science (AREA)
  • Mechanical Engineering (AREA)
  • Robotics (AREA)
  • Chemical & Material Sciences (AREA)
  • Combustion & Propulsion (AREA)
  • Transportation (AREA)
  • Manipulator (AREA)

Abstract

一种双足机器人步态生成与优化方法,在有限状态机中,根据双足机器人的状态的目标位姿构建双足机器人的步态库;设定触发机器人各状态之间相互切换条件;在每个状态切换过程中,利用关节三次插值法对支撑腿的运动轨迹进行规划,利用高斯伪谱法对摆动腿的运动轨迹进行优化;最终由有限状态机生成双足机器人多种不同运动模式的步态。所述双足机器人步态生成与优化方法,不考虑ZMP的约束,有无脚底边的双足机器人都可以使用该方法生成步行轨迹,使得规划过程简单可操作,更适合在线生成,配合简单的控制策略就可以使得双足步行机器人稳定行走,完成走、跑、跳等动作。

Description

一种双足机器人步态生成与优化方法 技术领域
本发明属于仿人机器人技术领域,具体涉及一种双足机器人步态生成与优化方法。
背景技术
双足机器人具有人类外形特征,采用双足行走、双手作业,易于适应人类工作环境和使用人类工具等特点,使其在老龄化社会家庭服务、公共安全等危险环境作业、国防等领域具有重大应用需求。虽然现今双足机器人在结构化环境中的运动规划、平衡控制、作业以及系统集成方面取得了标志性成果,但相比于工业机器人在工业生产的广泛应用,双足机器人离实际应用还有较大的差距。双足机器人的行走步态直接影响机器人的行走性能,不同的步态具有不同的稳定性、能效、拟人化程度等特点,因而设计一个合理的行走步态十分重要。人类具有不同的行走步态以适应不同的行走环境,创建一套方便实现不同行走步态的算法将有助于提升双足机器人的性能,提升其实用性。当机器人实际行走过程中容易受到外界环境因素的干扰而偏离规划的参考值,采用一定的控制算法对关节进行控制使其回复到参考值继续跟踪预期目标是双足机器人行走过程必须考虑的问题之一。
当前对于双足机器人在行走步态规划和稳定控制算法的研究大多集中在基于动力学模型、模型预测控制等方面,往往需要复杂的轨迹规划及运算求解,鲜有考虑步态模式的快速生成与切换、摆动腿快速反馈与应对等方面的问题。所以需要产生一种能够在线规划、不简化及忽略双足机器人全身动力学因素的相互耦合、过程简单并适用于多种双足机器人的步态生成方法,并从双足机器人能耗角度出发对步态规划进行优化,得到运行规划。
现有技术中提出一种利用振荡神经元单元全向耦合生成脚掌和质心轨迹,利用传感器检测环境信息形成反馈回路得到步态轨迹;另外有一种球铰连杆双自由度拇指根部关节装置,采用双电机与螺纹连接、球铰和人字连杆机构等,综合实现拇指根部的独立摆动和贴合动作;还有人提出一种基于丝杠连杆机构的五指灵巧手手指侧摆与对掌机构,利用丝杠螺母与连杆系统实现手指基关节两自由度的运动。上述发明专利所提出的基关节传动方式,电机放置位置受被驱动对象限制大量占用手掌空间,增加手的重量降低灵活性,而且配合安装复杂精度要求高,没有驱动方式的通用性。
发明内容
为了解决现有技术中的不足,提出了一种双足机器人步态生成与优化方法,目的在于 提供一种普适性更高的双足机器人步态生成方法。
本发明所采用的技术方案如下:
一种双足机器人步态生成与优化方法,在有限状态机中,根据双足机器人的状态的目标位姿构建双足机器人的步态库;设定触发机器人各状态之间相互切换条件;在每个状态切换过程中,利用关节三次插值法对支撑腿的运动轨迹进行规划,利用高斯伪谱法对摆动腿的运动轨迹进行优化;最终由有限状态机生成双足机器人多种不同运动模式的步态。
进一步,所述切换条件包括人为触发、时间触发和事件触发,所述时间触发,为设定状态之间的持续时间,所述事件触发为机器人摆动腿是否触地。
进一步,所述双足机器人的状态包括:机器人双脚站立在地面上的初始状态、仅右脚支撑的状态、左脚触地的状态、左脚支撑的状态、右脚触地的状态和腾空状态。
进一步,所述关节三次插值法的过程为:根据前后两个状态的目标角度θ 12、前后两个状态的角速度
Figure PCTCN2019123181-appb-000001
和状态之间持续时间为T,当前状态持续时间为t时,三次插值后的当前参考角度θ和角速度
Figure PCTCN2019123181-appb-000002
为:
θ=a 0·s 3+a 1·s 2+a 2·s+a 3
Figure PCTCN2019123181-appb-000003
其中,
Figure PCTCN2019123181-appb-000004
a 3=θ 1,s=t/T。
进一步,所述高斯伪谱法对摆动腿的运动轨迹进行优化的方法为:
S1,构建机器人摆动腿的动力学方程:
Figure PCTCN2019123181-appb-000005
其中,M是关节空间的惯性矩阵,C是科氏力、离心力与重力的合力矢量,q sw是摆动腿髋关节与膝关节的角度,
Figure PCTCN2019123181-appb-000006
为摆动腿髋关节与膝关节的角速度,τ sw为驱动力矩;
S2,对摆动腿的动力学方程进行变形,得到:
Figure PCTCN2019123181-appb-000007
建立非线性状态方程
Figure PCTCN2019123181-appb-000008
其中,
Figure PCTCN2019123181-appb-000009
u=τ sw
S3,建立评价函数:
Figure PCTCN2019123181-appb-000010
其中,x e是末位时刻的状态,S、Q、R为权重矩阵;
S4,把动力学方程在高斯点上进行离散,用N个高斯点T 1,T 2,…,T N和初始端点T 0上的离散状态构造拉格朗日插值多项式去近似状态的时间历程:
Figure PCTCN2019123181-appb-000011
其中,x(T)为真实的状态时间历程,X(T)为由拉格朗日插值多项式近似得到的状态时间历程;L i(T)为拉格朗日插值基函数,i=0,1,…,N,
Figure PCTCN2019123181-appb-000012
S5,获得性能指标、边界条件和不等式约束,
Figure PCTCN2019123181-appb-000013
φ(X 0,t 0,X f,t f)=0
C(X k,U k,T k;t 0,t f)≤0
其中,
Figure PCTCN2019123181-appb-000014
为初末状态约束条件,t 0为开始时间,t f为结束时间,X 0为t 0时刻的状态时间历程,X f为t f时刻的状态时间历程,w k为高斯积分权重,g为分段积分函数即动力学方程的积分,T k为高斯点,X k=X(T k),U k=U(T k)为系统输入,k=0,1,…,N;
进一步,对摆动腿的脚部末端位置进行约束,摆动腿的脚部末端在竖直方向的位置应该大于0;
进一步,利用所述高斯伪谱法对摆动腿的运动轨迹优化,需要同时满足设定的全身动力学约束条件。
本发明的有益效果:
本发明提出了一种双足机器人步态生成与优化的方法,不简化双足机器人避免了由于模型不准确造成的误差,从而给控制增加难度;利用有限状态机的有限性和对称性规划双足机器人运行简化了规划过程,并采用全身动力学约束降低了双足机器人运行过程的能量损耗;由于没有ZMP的限制,使得该方法无论是在有脚底板还是点足的双足机器人上均可适用,提高了方法的普适性。
附图说明
图1是本发明双足机器人步态生成与优化方法的流程框图;
图2是双足机器人在行走过程中不同状态示意图;
图3是双足机器人不同模式的运动状态示意图。
具体实施方式
为了使本发明的目的、技术方案及优点更加清楚明白,以下结合附图及实施例,对本发明进行进一步详细说明。应当理解,此处所描述的具体实施例仅用于解释本发明,并不用于限定本发明。
一种双足机器人步态生成与优化方法如如图1所示:
如图2所示,双足机器人在行走过程中依据支撑腿不同而将机器人状态分为6种,分别是机器人双脚站立在地面上的初始状态、仅右脚支撑的状态1、左脚触地的状态2、左脚支撑的状态3、右脚触地的状态4和腾空状态,通过人体行走的状态信息设置关节目标角度与行走参考速度;在有限状态机中,根据双足机器人不同状态的目标位姿构建双足机器人的步态库。
设定触发机器人各状态之间相互切换条件,切换条件包括人为触发、时间触发和事件触发,在本实施例中,事件触发具体为机器人摆动腿是否触地;如图2,当人为输入控制指令后,机器人从初始状态开始运动,即利用人为触动;经过一段时间后达到状态1,机器人开始进入周期行走循环阶段。在周期行走阶段,4种状态之间的切换共设有2种切换条件,一种是时间触发,即设定当前状态持续运行时间是否达到0.2s,另一种是事件触发,即机器人摆动腿是否触地,切换规则为:当状态1切换至状态2、状态3切换至状态4的条件为当前状态持续运行时间是否达到0.2s,当状态2切换至状态3、状态4切换至状态1的条件为机器人摆动腿是否触地;由图2可以看出机器人的步态呈对称分布,这与人体行走的节律性周期运动是一致的。若机器人在行走过程中处于腾空状态,当机器人处于腾空状态时机器人将保持全身姿态不变而等待机器人落地,当检测到双脚均触地时将其转换至状态1。
由于步态库中的每一状态只表示机器人当前状态初始时刻的位姿,在两个状态间切换时,参考的关节轨迹会产生跳变,使机器人在执行规划轨迹时出现飞车现象(即不稳定现象),因此在两个状态目标角度间需要通过插值函数得到平滑的轨迹。由于支撑腿的角度变化较小,起到支撑作用,所以只使用三次插值函数进行简单的轨迹规划;对于摆动腿由于运动幅度大,对机器人的平衡稳定起到重要的作用,所以使用高斯伪谱法的优化方法进行插值规划。最终由有限状态机生成双足机器人多种不同运动模式的步态,具体过程如下:
利用关节三次插值法对支撑腿的运动轨迹进行插值的具体过程:
设两个状态的目标角度与角速度分别为θ 12
Figure PCTCN2019123181-appb-000015
状态之间持续时间为T,当前状态持续时间为t时,三次插值后的当前参考角度θ和角速度
Figure PCTCN2019123181-appb-000016
为:
Figure PCTCN2019123181-appb-000017
Figure PCTCN2019123181-appb-000018
Figure PCTCN2019123181-appb-000019
a 3=θ 1         (1)
s=t/T
θ=a 0·s 3+a 1·s 2+a 2·s+a 3
Figure PCTCN2019123181-appb-000020
a 0,a 1,a 2,a 3,s只是运算中的过程量,没有实际意义;
利用高斯伪谱法对摆动腿的运动轨迹进行优化的具体过程:
设定上身躯干为固定基座,机器人摆动腿的动力学方程为:
Figure PCTCN2019123181-appb-000021
M∈R 2×2是关节空间的惯性矩阵,C∈R 2×1是科氏力、离心力与重力的合力矢量,
Figure PCTCN2019123181-appb-000022
分别是摆动腿髋关节与膝关节的角度、摆动腿髋关节与膝关节角速度和摆动腿髋关节与膝关节驱动力矩,
Figure PCTCN2019123181-appb-000023
为摆动腿髋关节的角度,
Figure PCTCN2019123181-appb-000024
为摆动腿膝关节的角度,
Figure PCTCN2019123181-appb-000025
为摆动腿髋关节的角速度,
Figure PCTCN2019123181-appb-000026
为摆动腿膝关节的角速度,
Figure PCTCN2019123181-appb-000027
为摆动腿髋关节的驱动力矩,
Figure PCTCN2019123181-appb-000028
为摆动腿膝关节的驱动力矩。为了使用高斯伪谱法进行摆动腿的步态优化,必须对摆动腿的动力学方程进行变形,使其满足优化算法的需求。建立非线性状态方程:
Figure PCTCN2019123181-appb-000029
其中,
Figure PCTCN2019123181-appb-000030
u=τ sw为该系统的控制量。
根据摆动腿动力学方程可得角加速度表达式为:
Figure PCTCN2019123181-appb-000031
因此,状态方程为
Figure PCTCN2019123181-appb-000032
建立评价函数:
Figure PCTCN2019123181-appb-000033
其中,x e是末位时刻的状态,S、Q、R为权重矩阵,t为时间。
把动力学方程在高斯点上进行离散,将时间区间
Figure PCTCN2019123181-appb-000034
转换到T∈[-1,1],这个转化可以通过下式完成:
Figure PCTCN2019123181-appb-000035
转换后的T取代t成为独立变量,T=-1时对应t 0,T=1时对应t f;t 0为开始时间,t f为结束时间;
用N个高斯点T 1,T 2,…,T N和初始端点T 0=-1上的离散状态构造Lagrange插值多项式去近似状态的时间历程:
Figure PCTCN2019123181-appb-000036
其中,x(T)为真实的状态时间历程,X(T)为由Lagrange插值多项式近似得到的状态时间历程;L i(T)为Lagrange插值基函数,i=0,1,…,N。
Figure PCTCN2019123181-appb-000037
由此对仿人机器人的脚部末位时刻的位置进行约束的微分方程动态转化为一系列代数约束:
Figure PCTCN2019123181-appb-000038
式中:X k=X(T k),U k=U(T k),k=0,1,…,N;
性能指标、边界条件和不等式约束分别转化为:
Figure PCTCN2019123181-appb-000039
φ(X 0,t 0,X f,t f)=0     (12)
C(X k,U k,T k;t 0,t f)≤0      (13)
其中,w k为高斯积分权重。
由于摆动腿在整个运行周期必须保持在地面之上,避免与地面的碰撞,因此还需要对摆动腿的脚部末端位置进行约束,即摆动腿的脚部末端在竖直方向的位置应该大于0。
同时,高斯伪谱法对摆动腿的运动轨迹优化需要满足设定的全身动力学约束条件,构造机器人全身动力学方程的方法为:
Figure PCTCN2019123181-appb-000040
其中,D,N,G,B,J分别为与惯性、哥氏力、重力、力矩变换和雅克比有关的矩阵,F E是摆动腿末端受到的外界作用力,
Figure PCTCN2019123181-appb-000041
为机器人广义坐标躯干角度θ tor、支撑腿的髋关节角度
Figure PCTCN2019123181-appb-000042
与膝关节角度
Figure PCTCN2019123181-appb-000043
摆动腿的髋关节角度
Figure PCTCN2019123181-appb-000044
与膝关节角度
Figure PCTCN2019123181-appb-000045
Figure PCTCN2019123181-appb-000046
分别是其一阶和二阶导数。
经过仿真实验验证,本方法能够由有限状态机生成双足机器人多种不同运动模式的步态。如图3所示,可以形成多种不同模式的运动,包括慢步走、快步走、跳跃前进等。
相对于现有双足机器人步态生成方法需要建立简化模型,如倒立摆、车桌模型等,将机器人的运动分为多个阶段,然后对每个阶段单独考虑,首先规划足端或ZMP点的轨迹,然后再通过模型得到质心轨迹,最后通过腿部的逆运动学求解关节的时间序列,从而生成步行模式,本发明通过状态机来生成不同的机器人的运动模式,简化了规划过程,并采用全身动力学约束降低了双足机器人运行过程的能量损耗;由于没有ZMP的限制,使得该方法无论是在有脚底板还是点足的双足机器人上均可适用,提高了方法的普适性。
以上实施例仅用于说明本发明的设计思想和特点,其目的在于使本领域内的技术人员能够了解本发明的内容并据以实施,本发明的保护范围不限于上述实施例。所以,凡依据本发明所揭示的原理、设计思路所作的等同变化或修饰,均在本发明的保护范围之内。

Claims (7)

  1. 一种双足机器人步态生成与优化方法,其特征在于,在有限状态机中,根据双足机器人的状态的目标位姿构建双足机器人的步态库;设定触发机器人各状态之间相互切换条件;在每个状态切换过程中,利用关节三次插值法对支撑腿的运动轨迹进行规划,利用高斯伪谱法对摆动腿的运动轨迹进行优化;最终由有限状态机生成双足机器人多种不同运动模式的步态。
  2. 根据权利要求1所述的一种双足机器人步态生成与优化方法,其特征在于,所述切换条件包括人为触发、时间触发和事件触发,所述时间触发,为设定状态之间的持续时间,所述事件触发为机器人摆动腿是否触地。
  3. 根据权利要求1所述的一种双足机器人步态生成与优化方法,其特征在于,所述双足机器人的状态包括:机器人双脚站立在地面上的初始状态、仅右脚支撑的状态、左脚触地的状态、左脚支撑的状态、右脚触地的状态和腾空状态。
  4. 根据权利要求1所述的一种双足机器人步态生成与优化方法,其特征在于,所述关节三次插值法的过程为:根据前后两个状态的目标角度θ 12、前后两个状态的角速度
    Figure PCTCN2019123181-appb-100001
    和状态之间持续时间为T,当前状态持续时间为t时,三次插值后的当前参考角度θ和角速度
    Figure PCTCN2019123181-appb-100002
    为:
    θ=a 0·s 3+a 1·s 2+a 2·s+a 3
    Figure PCTCN2019123181-appb-100003
    其中,
    Figure PCTCN2019123181-appb-100004
    a 3=θ 1,s=t/T。
  5. 根据权利要求1所述的一种双足机器人步态生成与优化方法,其特征在于,所述高斯伪谱法对摆动腿的运动轨迹进行优化的方法为:
    S1,构建机器人摆动腿的动力学方程:
    Figure PCTCN2019123181-appb-100005
    其中,M是关节空间的惯性矩阵,C是科氏力、离心力与重力的合力矢量,q sw是摆动腿髋关节与膝关节的角度,
    Figure PCTCN2019123181-appb-100006
    为摆动腿髋关节与膝关节的角速度,τ sw为驱动力矩;
    S2,对摆动腿的动力学方程进行变形,得到:
    Figure PCTCN2019123181-appb-100007
    建立非 线性状态方程
    Figure PCTCN2019123181-appb-100008
    其中,
    Figure PCTCN2019123181-appb-100009
    u=τ sw
    S3,建立评价函数:
    Figure PCTCN2019123181-appb-100010
    其中,x e是末位时刻的状态,S、Q、R为权重矩阵;
    S4,把动力学方程在高斯点上进行离散,用N个高斯点T 1,T 2,…,T N和初始端点T 0上的离散状态构造拉格朗日插值多项式去近似状态的时间历程:
    Figure PCTCN2019123181-appb-100011
    其中,x(T)为真实的状态时间历程,X(T)为由拉格朗日插值多项式近似得到的状态时间历程;L i(T)为拉格朗日插值基函数,i=0,1,…,N,
    Figure PCTCN2019123181-appb-100012
    S5,获得性能指标、边界条件和不等式约束,
    Figure PCTCN2019123181-appb-100013
    φ(X 0,t 0,X f,t f)=0
    C(X k,U k,T k;t 0,t f)≤0
    其中,
    Figure PCTCN2019123181-appb-100014
    为初末状态约束条件,t 0为开始时间,t f为结束时间,X 0为t 0时刻的状态时间历程,X f为t f时刻的状态时间历程,w k为高斯积分权重,g为分段积分函数即动力学方程的积分,T k为高斯点,X k=X(T k),U k=U(T k)为系统输入,k=0,1,…,N。
  6. 根据权利要求5所述的一种双足机器人步态生成与优化方法,其特征在于,对摆动腿的脚部末端位置进行约束,摆动腿的脚部末端在竖直方向的位置应该大于0。
  7. 根据权利要求6所述的一种双足机器人步态生成与优化方法,其特征在于,利用所述高斯伪谱法对摆动腿的运动轨迹优化,需要同时满足设定的全身动力学约束条件。
PCT/CN2019/123181 2019-07-29 2019-12-05 一种双足机器人步态生成与优化方法 WO2021017356A1 (zh)

Applications Claiming Priority (2)

Application Number Priority Date Filing Date Title
CN201910688948.3A CN110315543B (zh) 2019-07-29 2019-07-29 一种双足机器人步态生成与优化方法
CN201910688948.3 2019-07-29

Publications (1)

Publication Number Publication Date
WO2021017356A1 true WO2021017356A1 (zh) 2021-02-04

Family

ID=68124810

Family Applications (1)

Application Number Title Priority Date Filing Date
PCT/CN2019/123181 WO2021017356A1 (zh) 2019-07-29 2019-12-05 一种双足机器人步态生成与优化方法

Country Status (2)

Country Link
CN (1) CN110315543B (zh)
WO (1) WO2021017356A1 (zh)

Families Citing this family (21)

* Cited by examiner, † Cited by third party
Publication number Priority date Publication date Assignee Title
CN110315543B (zh) * 2019-07-29 2021-02-26 北京理工大学 一种双足机器人步态生成与优化方法
CN111230868B (zh) * 2020-01-19 2022-01-04 之江实验室 双足机器人在前进方向受到外部推力扰动时的步态规划与控制方法
CN113156926B (zh) * 2020-01-22 2024-05-17 深圳市优必选科技股份有限公司 机器人的有限状态机的建立方法、有限状态机和机器人
CN111176342B (zh) * 2020-02-11 2021-03-30 之江实验室 一种双足机器人仿人步态的步行速度调节方法
CN113326722B (zh) * 2020-02-29 2023-06-02 湖南超能机器人技术有限公司 基于序列模式的图像模糊检测方法及设备
CN111114668B (zh) * 2020-03-27 2020-07-07 之江实验室 基于关节工况多象限耦合的双足机器人数字液压驱动方法
CN111880544B (zh) * 2020-08-07 2024-03-22 深圳市优必选科技股份有限公司 仿人机器人步态规划方法、装置和仿人机器人
CN112123340B (zh) * 2020-10-21 2021-08-24 乐聚(深圳)机器人技术有限公司 机器人运动控制方法、装置、机器人及存储介质
CN112091984B (zh) * 2020-11-17 2021-04-20 深圳市优必选科技股份有限公司 双足机器人的步态纠偏方法、装置和计算机设备
CN112720462B (zh) * 2020-12-09 2021-08-27 深圳先进技术研究院 一种机器人的轨迹规划系统和方法
CN112650234B (zh) * 2020-12-16 2022-05-17 浙江大学 一种双足机器人的路径规划方法
CN112947065B (zh) * 2021-01-25 2022-09-16 河南大学 一种双足机器人行走实时步态的azr调节方法
CN112918585A (zh) * 2021-02-20 2021-06-08 杭州三因云信息技术有限公司 一种欠驱动双足步行机器人的步态控制方法
CN113081582B (zh) * 2021-03-18 2022-06-28 上海交通大学 一种机器人辅助站立轨迹生成方法
CN115188063A (zh) * 2021-04-06 2022-10-14 广州视源电子科技股份有限公司 基于跑步机的跑姿分析方法、装置、跑步机及存储介质
CN113110484A (zh) * 2021-04-30 2021-07-13 深圳市优必选科技股份有限公司 一种步态轨迹规划方法、装置、可读存储介质及机器人
CN113753150B (zh) * 2021-05-31 2024-01-12 腾讯科技(深圳)有限公司 轮腿式机器人的控制方法、装置、设备及可读存储介质
CN113244090B (zh) * 2021-07-16 2021-09-14 中国科学院自动化研究所 髋关节下肢外骨骼控制方法、装置、电子设备和存储介质
CN114248855B (zh) * 2021-12-20 2022-10-21 北京理工大学 双足机器人空间域步态规划与控制的方法
CN114326769B (zh) * 2021-12-28 2024-03-29 深圳市优必选科技股份有限公司 机器人运动矫正方法及装置、机器人控制设备和存储介质
CN114625129B (zh) * 2022-02-22 2023-09-12 中国科学院自动化研究所 位控腿足机器人的运动控制方法及系统

Citations (5)

* Cited by examiner, † Cited by third party
Publication number Priority date Publication date Assignee Title
CN1590039A (zh) * 2003-08-25 2005-03-09 索尼株式会社 机器人及机器人的姿态控制方法
CN103955220A (zh) * 2014-04-30 2014-07-30 西北工业大学 一种空间绳系机器人跟踪最优轨迹协调控制方法
US8855821B2 (en) * 2011-05-30 2014-10-07 Samsung Electronics Co., Ltd. Robot and control method thereof
CN106647282A (zh) * 2017-01-19 2017-05-10 北京工业大学 一种考虑末端运动误差的六自由度机器人轨迹规划方法
CN110315543A (zh) * 2019-07-29 2019-10-11 北京理工大学 一种双足机器人步态生成与优化方法

Family Cites Families (4)

* Cited by examiner, † Cited by third party
Publication number Priority date Publication date Assignee Title
WO2005068136A1 (ja) * 2004-01-13 2005-07-28 Honda Motor Co., Ltd. 移動ロボットの歩容生成装置
CN105388755B (zh) * 2015-05-12 2018-08-24 北京理工大学 一种仿人机器人摆动腿迈步的能效优化控制方法
CN106985140B (zh) * 2017-04-19 2019-05-07 广州视源电子科技股份有限公司 机器人点到点运动控制方法和系统
CN110039544A (zh) * 2019-04-28 2019-07-23 南京邮电大学 基于三次样条插值的仿人足球机器人步态规划

Patent Citations (5)

* Cited by examiner, † Cited by third party
Publication number Priority date Publication date Assignee Title
CN1590039A (zh) * 2003-08-25 2005-03-09 索尼株式会社 机器人及机器人的姿态控制方法
US8855821B2 (en) * 2011-05-30 2014-10-07 Samsung Electronics Co., Ltd. Robot and control method thereof
CN103955220A (zh) * 2014-04-30 2014-07-30 西北工业大学 一种空间绳系机器人跟踪最优轨迹协调控制方法
CN106647282A (zh) * 2017-01-19 2017-05-10 北京工业大学 一种考虑末端运动误差的六自由度机器人轨迹规划方法
CN110315543A (zh) * 2019-07-29 2019-10-11 北京理工大学 一种双足机器人步态生成与优化方法

Also Published As

Publication number Publication date
CN110315543B (zh) 2021-02-26
CN110315543A (zh) 2019-10-11

Similar Documents

Publication Publication Date Title
WO2021017356A1 (zh) 一种双足机器人步态生成与优化方法
JP6501921B2 (ja) 二足ロボットの歩行制御方法及び歩行制御装置
Bessonnet et al. A parametric optimization approach to walking pattern synthesis
CN110405762B (zh) 一种基于空间二阶倒立摆模型的双足机器人姿态控制方法
Dip et al. Genetic algorithm-based optimal bipedal walking gait synthesis considering tradeoff between stability margin and speed
JP5052013B2 (ja) ロボット装置及びその制御方法
Chew et al. Dynamic bipedal walking assisted by learning
Denk et al. Synthesis of a walking primitive database for a humanoid robot using optimal control techniques
Harata et al. Biped gait generation based on parametric excitation by knee-joint actuation
Asano et al. On energy-efficient and high-speed dynamic biped locomotion with semicircular feet
Aloulou et al. Minimum jerk-based control for a three dimensional bipedal robot
Inoue et al. Mobile manipulation of humanoid robots-body and leg control for dual arm manipulation
Wang et al. Realization of a real-time optimal control strategy to stabilize a falling humanoid robot with hand contact
CN114986526A (zh) 机器人运动控制方法、装置、机器人及存储介质
Sadigh et al. Application of phase-plane method in generating minimum time solution for stable walking of biped robot with specified pattern of Motion
JP3677623B2 (ja) 脚式ロボットのリアルタイム最適制御方法
Lim et al. Optimal gait primitives for dynamic bipedal locomotion
Chang et al. Study on falling backward of humanoid robot based on dynamic multi objective optimization
Hayashia et al. Experimental study of dynamic bipedal walking based on the principle of parametric excitation with counterweights
Zhang et al. Optimal energy gait planning for humanoid robot using geodesics
Chen et al. Optimized 3D stable walking of a bipedal robot with line-shaped massless feet and sagittal underactuation
Liu et al. Stable walking control of parallel wheel-foot robot based on ZMP theory
Hao et al. On-demand optimal gait generation for a compass biped robot based on the double generating function method
Yilmaz et al. Circular arc-shaped walking trajectory generation for bipedal humanoid robots
Feng et al. Humanoid robot field-programmable gate array hardware and robot-operating-system-based software machine co-design

Legal Events

Date Code Title Description
121 Ep: the epo has been informed by wipo that ep was designated in this application

Ref document number: 19939316

Country of ref document: EP

Kind code of ref document: A1

NENP Non-entry into the national phase

Ref country code: DE

122 Ep: pct application non-entry in european phase

Ref document number: 19939316

Country of ref document: EP

Kind code of ref document: A1

32PN Ep: public notification in the ep bulletin as address of the adressee cannot be established

Free format text: NOTING OF LOSS OF RIGHTS PURSUANT TO RULE 112(1) EPC (EPO FORM 1205A DATED 29/03/2023)

122 Ep: pct application non-entry in european phase

Ref document number: 19939316

Country of ref document: EP

Kind code of ref document: A1