mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_Scripting: quadruped.lua logic test fix
This commit is contained in:
parent
a4c7aa6386
commit
f344363404
@ -130,7 +130,7 @@ function update_leg(moving_leg)
|
|||||||
local leg_step = gait_step - gait_step_leg_start[moving_leg]
|
local leg_step = gait_step - gait_step_leg_start[moving_leg]
|
||||||
local move_requested = (math.abs(x_speed) > speed_dz) or (math.abs(y_speed) > speed_dz) or (math.abs(yaw_speed) > speed_dz)
|
local move_requested = (math.abs(x_speed) > speed_dz) or (math.abs(y_speed) > speed_dz) or (math.abs(yaw_speed) > speed_dz)
|
||||||
|
|
||||||
if ((move_requested and (gait_lifted_steps and 1) and leg_step==0) or
|
if ((move_requested and (gait_lifted_steps > 0) and leg_step==0) or
|
||||||
(not move_requested and leg_step==0 and ((gait_pos_x[moving_leg]>2) or
|
(not move_requested and leg_step==0 and ((gait_pos_x[moving_leg]>2) or
|
||||||
(gait_pos_z[moving_leg]>2) or (gait_rot_z[moving_leg] >2)))) then
|
(gait_pos_z[moving_leg]>2) or (gait_rot_z[moving_leg] >2)))) then
|
||||||
gait_pos_x[moving_leg] = 0
|
gait_pos_x[moving_leg] = 0
|
||||||
|
Loading…
Reference in New Issue
Block a user