本章需要在机械臂逆运动学(tar-tip)完成的前提下完成
传送门:CoppeliaSim(原Vrep)中实现多关节机械臂的逆运动学仿真(tar-tip)
1)add -> dummy 添加path的路径点
设置好位置后按顺序将dummy重命名为同样的==“字符串+数字排序”==(例如:tar1,tar2,tar3)
为了之后在程序中用for循环遍历dummy句柄
2)代码实现
function sysCall_threadmain()
-- Put some initialization code here
-- 初始化 获取变量句柄
jointHandles={}
for i = 1,4,1 do
jointHandles[i] = sim.getObjectHandle('4j_Joint'..i)
end
ikTip = sim.getObjectHandle('RRRR_Tip')
ikTarget = sim.getObjectHandle('RRRR_Tar')
tarHandles = {}
for i = 1,6 do -- 注意for循环区间要和有几个点对应
tarHandles[i] = sim.getObjectHandle('tar'..i)
end
-- 设置机械臂的关节空间运动属性
--[[
local accel = 0.5
local jerk = 0.5
local vel = 0.5
local currentVel = {0,0,0,0}
local currentAccel = {0,0,0,0}
local maxVel = {vel,vel,vel,1.5*vel}
local maxAccel = {accel,accel,accel,accel}
local maxJerk = {jerk,jerk,jerk,jerk}
local targetVel = {0,0,0,0}
]]
-- 设置笛卡尔空间运动属性,设置的是到达点的参数,有几个tar写几个值
local currentVel = {0,0,0,0,0,0}
local currentAccel = {0,0,0,0,0,0}
local maxVel = {0.2,0.2,0.2,0.2,0.2,0.2}
local maxAccel = {1,1,1,1,1,1}
local maxJerk = {1,1,1,1,1,1}
local targetPos = {0,0,0,0,0,0}
local targetVel = {0,0,0,0,0,0}
-- 主循环
while sim.getSimulationState()~=sim.simulation_advancing_abouttostop do
for i = 1,6 do
sim.rmlMoveToPosition(ikTarget,tarHandles[i],-1,currentVel,currentAccel,maxVel,maxAccel,maxJerk,targetPos,nil,targetVel)
-- 阻塞式函数,只能单步执行,当有多个机械臂时,只有一个动,其他不动
end
end
end
function sysCall_cleanup()
-- Put some clean-up code here
-- See the user manual or the available code snippets for additional callback functions and details
end
3)运行结果(跟上面代码不完全一样,本视频有24个路径点)
机械臂逆运动学路径