Skip to content

Commit

Permalink
fix scanning error (AtsushiSakai#339)
Browse files Browse the repository at this point in the history
  • Loading branch information
AtsushiSakai authored Jun 8, 2020
1 parent a36ddb4 commit fa1585d
Show file tree
Hide file tree
Showing 11 changed files with 487 additions and 392 deletions.
16 changes: 9 additions & 7 deletions ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,21 +11,23 @@ def random_val(min_val, max_val):
return min_val + random.random() * (max_val - min_val)


if __name__ == "__main__":
def main():
print("Start solving Forward Kinematics 10 times")

# init NLinkArm with Denavit-Hartenberg parameters of PR2
# init NLinkArm with Denavit-Hartenberg parameters of PR2
n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.],
[math.pi / 2, math.pi / 2, 0., 0.],
[0., -math.pi / 2, 0., .4],
[0., math.pi / 2, 0., 0.],
[0., -math.pi / 2, 0., .321],
[0., math.pi / 2, 0., 0.],
[0., 0., 0., 0.]])

# execute FK 10 times
for i in range(10):
for _ in range(10):
n_link_arm.set_joint_angles(
[random_val(-1, 1) for j in range(len(n_link_arm.link_list))])
[random_val(-1, 1) for _ in range(len(n_link_arm.link_list))])

ee_pose = n_link_arm.forward_kinematics(plot=True)
n_link_arm.forward_kinematics(plot=True)


if __name__ == "__main__":
main()
12 changes: 7 additions & 5 deletions ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,23 +11,25 @@ def random_val(min_val, max_val):
return min_val + random.random() * (max_val - min_val)


if __name__ == "__main__":
def main():
print("Start solving Inverse Kinematics 10 times")

# init NLinkArm with Denavit-Hartenberg parameters of PR2
# init NLinkArm with Denavit-Hartenberg parameters of PR2
n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.],
[math.pi / 2, math.pi / 2, 0., 0.],
[0., -math.pi / 2, 0., .4],
[0., math.pi / 2, 0., 0.],
[0., -math.pi / 2, 0., .321],
[0., math.pi / 2, 0., 0.],
[0., 0., 0., 0.]])

# execute IK 10 times
for i in range(10):
for _ in range(10):
n_link_arm.inverse_kinematics([random_val(-0.5, 0.5),
random_val(-0.5, 0.5),
random_val(-0.5, 0.5),
random_val(-0.5, 0.5),
random_val(-0.5, 0.5),
random_val(-0.5, 0.5)], plot=True)


if __name__ == "__main__":
main()
3 changes: 1 addition & 2 deletions Bipedal/bipedal_planner/bipedal_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,8 @@ def walk(self, t_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
print("No footsteps")
return

com_trajectory_for_plot, ax = None, None

# set up plotter
com_trajectory_for_plot, ax = None, None
if plot:
fig = plt.figure()
ax = Axes3D(fig)
Expand Down
28 changes: 16 additions & 12 deletions InvertedPendulumCart/inverted_pendulum_mpc_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,12 @@
author: Atsushi Sakai
"""

import matplotlib.pyplot as plt
import numpy as np
import math
import time

import cvxpy
import matplotlib.pyplot as plt
import numpy as np

# Model parameters

Expand Down Expand Up @@ -39,10 +40,11 @@ def main():
for i in range(50):

# calc control input
optimized_x, optimized_delta_x, optimized_theta, optimized_delta_theta, optimized_input = mpc_control(x)
opt_x, opt_delta_x, opt_theta, opt_delta_theta, opt_input = \
mpc_control(x)

# get input
u = optimized_input[0]
u = opt_input[0]

# simulate inverted pendulum cart
x = simulation(x, u)
Expand Down Expand Up @@ -86,17 +88,19 @@ def mpc_control(x0):
print("calc time:{0} [sec]".format(elapsed_time))

if prob.status == cvxpy.OPTIMAL:
ox = get_nparray_from_matrix(x.value[0, :])
dx = get_nparray_from_matrix(x.value[1, :])
theta = get_nparray_from_matrix(x.value[2, :])
dtheta = get_nparray_from_matrix(x.value[3, :])
ox = get_numpy_array_from_matrix(x.value[0, :])
dx = get_numpy_array_from_matrix(x.value[1, :])
theta = get_numpy_array_from_matrix(x.value[2, :])
d_theta = get_numpy_array_from_matrix(x.value[3, :])

ou = get_nparray_from_matrix(u.value[0, :])
ou = get_numpy_array_from_matrix(u.value[0, :])
else:
ox, dx, theta, d_theta, ou = None, None, None, None, None

return ox, dx, theta, dtheta, ou
return ox, dx, theta, d_theta, ou


def get_nparray_from_matrix(x):
def get_numpy_array_from_matrix(x):
"""
get build-in list from matrix
"""
Expand Down Expand Up @@ -133,7 +137,7 @@ def plot_cart(xt, theta):
radius = 0.1

cx = np.array([-cart_w / 2.0, cart_w / 2.0, cart_w /
2.0, -cart_w / 2.0, -cart_w / 2.0])
2.0, -cart_w / 2.0, -cart_w / 2.0])
cy = np.array([0.0, 0.0, cart_h, cart_h, 0.0])
cy += radius * 2.0

Expand Down
3 changes: 2 additions & 1 deletion Mapping/lidar_to_grid_map/lidar_to_grid_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@ def file_read(f):
"""
Reading LIDAR laser beams (angles and corresponding distance data)
"""
measures = [line.split(",") for line in open(f)]
with open(f) as data:
measures = [line.split(",") for line in data]
angles = []
distances = []
for measure in measures:
Expand Down
Loading

0 comments on commit fa1585d

Please sign in to comment.