Skip to content

Commit

Permalink
Rename class from Point to Vector (#93)
Browse files Browse the repository at this point in the history
  • Loading branch information
guilyx authored Apr 29, 2020
1 parent 5d0d7be commit 9903c16
Show file tree
Hide file tree
Showing 13 changed files with 196 additions and 195 deletions.
4 changes: 2 additions & 2 deletions hexapod/ground_contact_solver/shared.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
from math import isclose
from hexapod.points import (
Point,
Vector,
dot,
cross,
vector_from_to,
Expand Down Expand Up @@ -48,7 +48,7 @@ def is_stable(p1, p2, p3, tol=0.001):
onto the plane defined by p1, p2, p3
is within a triangle defined by p1, p2, p3.
"""
p = Point(0, 0, 0)
p = Vector(0, 0, 0)
u = vector_from_to(p1, p2)
v = vector_from_to(p1, p3)
n = cross(u, v)
Expand Down
14 changes: 7 additions & 7 deletions hexapod/ik_solver/ik_solver.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
might_print_points,
)
from hexapod.points import (
Point,
Vector,
length,
add_vectors,
scalar_multiply,
Expand Down Expand Up @@ -60,7 +60,7 @@ def inverse_kinematics_update(hexapod, ik_parameters):
if body_contact_shoved_on_ground(hexapod):
raise Exception(BODY_ON_GROUND_ALERT_MSG)

x_axis = Point(1, 0, 0)
x_axis = Vector(1, 0, 0)
legs_up_in_the_air = []

for i in range(hexapod.LEG_COUNT):
Expand All @@ -83,15 +83,15 @@ def inverse_kinematics_update(hexapod, ik_parameters):
# *******************
# 1. Compute p0, p1 and (possible) p3 wrt leg frame
# *******************
p0 = Point(0, 0, 0)
p1 = Point(hexapod.coxia, 0, 0)
p0 = Vector(0, 0, 0)
p1 = Vector(hexapod.coxia, 0, 0)

# Find p3 aka foot tip (ground contact) with respect to the local leg frame
rho = angle_between(unit_coxia_vector, body_to_foot_vector)
body_to_foot_length = length(body_to_foot_vector)
p3x = body_to_foot_length * np.cos(np.radians(rho))
p3z = -body_to_foot_length * np.sin(np.radians(rho))
p3 = Point(p3x, 0, p3z)
p3 = Vector(p3x, 0, p3z)

# *******************
# 2. Compute p2, beta, gamma and final p3 wrt leg frame
Expand Down Expand Up @@ -119,7 +119,7 @@ def inverse_kinematics_update(hexapod, ik_parameters):
z_ = hexapod.femur * np.sin(np.radians(beta))
x_ = p1.x + hexapod.femur * np.cos(np.radians(beta))

p2 = Point(x_, 0, z_)
p2 = Vector(x_, 0, z_)
femur_vector = vector_from_to(p1, p2)
tibia_vector = vector_from_to(p2, p3)
gamma = 90 - angle_between(femur_vector, tibia_vector)
Expand Down Expand Up @@ -149,7 +149,7 @@ def inverse_kinematics_update(hexapod, ik_parameters):

# Find beta and gamma
gamma = 0.0
leg_x_axis = Point(1, 0, 0)
leg_x_axis = Vector(1, 0, 0)
beta = angle_between(leg_x_axis, femur_vector)
if femur_vector.z < 0:
beta = -beta
Expand Down
12 changes: 6 additions & 6 deletions hexapod/ik_solver/ik_solver2.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
might_print_points,
)
from hexapod.points import (
Point,
Vector,
length,
add_vectors,
scalar_multiply,
Expand Down Expand Up @@ -85,7 +85,7 @@ class IKSolver:
def __init__(self, hexapod, ik_parameters):
self.hexapod = hexapod
self.params = ik_parameters
self.leg_x_axis = Point(1, 0, 0)
self.leg_x_axis = Vector(1, 0, 0)
self.update_body_and_ground_contact_points()
self.poses = deepcopy(HEXAPOD_POSE)

Expand Down Expand Up @@ -149,15 +149,15 @@ def store_initial_vectors(self):
raise Exception(COXIA_ON_GROUND_ALERT_MSG)

def compute_local_p0_p1_p3(self):
self.p0 = Point(0, 0, 0)
self.p1 = Point(self.hexapod.coxia, 0, 0)
self.p0 = Vector(0, 0, 0)
self.p1 = Vector(self.hexapod.coxia, 0, 0)

# Find p3 aka foot tip (ground contact) with respect to the local leg frame
rho = angle_between(self.unit_coxia_vector, self.body_to_foot_vector)
body_to_foot_length = length(self.body_to_foot_vector)
p3x = body_to_foot_length * np.cos(np.radians(rho))
p3z = -body_to_foot_length * np.sin(np.radians(rho))
self.p3 = Point(p3x, 0, p3z)
self.p3 = Vector(p3x, 0, p3z)

def compute_beta_gamma_local_p2(self):
# These values are needed to compute
Expand Down Expand Up @@ -194,7 +194,7 @@ def compute_when_triangle_can_form(self):
z_ = self.hexapod.femur * np.sin(np.radians(self.beta))
x_ = self.p1.x + self.hexapod.femur * np.cos(np.radians(self.beta))

self.p2 = Point(x_, 0, z_)
self.p2 = Vector(x_, 0, z_)
femur_vector = vector_from_to(self.p1, self.p2)
tibia_vector = vector_from_to(self.p2, self.p3)
self.gamma = 90 - angle_between(femur_vector, tibia_vector)
Expand Down
6 changes: 3 additions & 3 deletions hexapod/ik_solver/recompute_hexapod.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
from hexapod.points import (
angle_between,
is_counter_clockwise,
Point,
Vector,
rotz,
vector_from_to,
length,
Expand Down Expand Up @@ -91,7 +91,7 @@ def find_two_same_leg_ids(old_contacts, new_contacts):

def find_twist_to_recompute_hexapod(a, b):
twist = angle_between(a, b)
z_axis = Point(0, 0, -1)
z_axis = Vector(0, 0, -1)
is_ccw = is_counter_clockwise(a, b, z_axis)
if is_ccw:
twist = -twist
Expand All @@ -101,7 +101,7 @@ def find_twist_to_recompute_hexapod(a, b):


def should_be_on_ground_msg(point):
return f"Point should be on the ground:\n{point}, z != 0"
return f"Vector should be on the ground:\n{point}, z != 0"


def might_sanity_check_points(new_p1, new_p2, old_p1, old_p2, new_vector, old_vector):
Expand Down
8 changes: 4 additions & 4 deletions hexapod/linkage.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@
from copy import deepcopy
import numpy as np
from hexapod.points import (
Point,
Vector,
frame_yrotate_xtranslate,
frame_zrotate_xytranslate,
)
Expand Down Expand Up @@ -92,7 +92,7 @@ def __init__(
beta=0,
gamma=0,
coxia_axis=0,
new_origin=Point(0, 0, 0),
new_origin=Vector(0, 0, 0),
name=None,
id_number=None,
):
Expand Down Expand Up @@ -143,7 +143,7 @@ def change_pose(self, alpha, beta, gamma):
)

# find points wrt to body contact point
p0 = Point(0, 0, 0)
p0 = Vector(0, 0, 0)
p1 = p0.get_point_wrt(frame_01)
p2 = p0.get_point_wrt(frame_02)
p3 = p0.get_point_wrt(frame_03)
Expand Down Expand Up @@ -174,7 +174,7 @@ def compute_ground_contact(self):

def __str__(self):
leg_string = f"{self!r}\n"
leg_string += f"Points of {self.name} leg:\n"
leg_string += f"Vectors of {self.name} leg:\n"

for point in self.all_points:
leg_string += f" {point}\n"
Expand Down
30 changes: 15 additions & 15 deletions hexapod/models.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

from hexapod.templates.pose_template import HEXAPOD_POSE
from hexapod.points import (
Point,
Vector,
frame_to_align_vector_a_to_b,
frame_rotxyz,
rotz,
Expand Down Expand Up @@ -75,15 +75,15 @@ def __init__(self, f, m, s):
self.m = m
self.s = s

self.cog = Point(0, 0, 0, name="center-of-gravity")
self.head = Point(0, s, 0, name="head")
self.cog = Vector(0, 0, 0, name="center-of-gravity")
self.head = Vector(0, s, 0, name="head")
self.vertices = [
Point(m, 0, 0, name=Hexagon.VERTEX_NAMES[0]),
Point(f, s, 0, name=Hexagon.VERTEX_NAMES[1]),
Point(-f, s, 0, name=Hexagon.VERTEX_NAMES[2]),
Point(-m, 0, 0, name=Hexagon.VERTEX_NAMES[3]),
Point(-f, -s, 0, name=Hexagon.VERTEX_NAMES[4]),
Point(f, -s, 0, name=Hexagon.VERTEX_NAMES[5]),
Vector(m, 0, 0, name=Hexagon.VERTEX_NAMES[0]),
Vector(f, s, 0, name=Hexagon.VERTEX_NAMES[1]),
Vector(-f, s, 0, name=Hexagon.VERTEX_NAMES[2]),
Vector(-m, 0, 0, name=Hexagon.VERTEX_NAMES[3]),
Vector(-f, -s, 0, name=Hexagon.VERTEX_NAMES[4]),
Vector(f, -s, 0, name=Hexagon.VERTEX_NAMES[5]),
]

self.all_points = self.vertices + [self.cog, self.head]
Expand Down Expand Up @@ -139,7 +139,7 @@ def update(self, poses, assume_ground_targets=True):
raise Exception("❗Pose Unstable. COG not inside support polygon.")

# Tilt and shift the hexapod based on new normal
frame = frame_to_align_vector_a_to_b(n_axis, Point(0, 0, 1))
frame = frame_to_align_vector_a_to_b(n_axis, Vector(0, 0, 1))
self.rotate_and_shift(frame, height)
self._update_local_frame(frame)

Expand Down Expand Up @@ -225,9 +225,9 @@ def rotate_and_shift(self, frame, height=0):
leg.update_leg_wrt(frame, height)

def _init_local_frame(self):
self.x_axis = Point(1, 0, 0, name="hexapod x axis")
self.y_axis = Point(0, 1, 0, name="hexapod y axis")
self.z_axis = Point(0, 0, 1, name="hexapod z axis")
self.x_axis = Vector(1, 0, 0, name="hexapod x axis")
self.y_axis = Vector(0, 1, 0, name="hexapod y axis")
self.z_axis = Vector(0, 0, 1, name="hexapod z axis")

def _update_local_frame(self, frame):
# Update the x, y, z axis centered at cog of hexapod
Expand Down Expand Up @@ -310,8 +310,8 @@ def _twist(v1, v2):
new = new_contacts[same_point_name]

# Get the projection of these points in the ground
old_vector = Point(old.x, old.y, 0)
new_vector = Point(new.x, new.y, 0)
old_vector = Vector(old.x, old.y, 0)
new_vector = Vector(new.x, new.y, 0)

twist_frame = _twist(new_vector, old_vector)

Expand Down
23 changes: 12 additions & 11 deletions hexapod/points.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# This module contains the Point class
# This module contains the Vector class
# and functions for manipulating vectors
# and finding properties and relationships of vectors
# computing reference frames
Expand All @@ -8,7 +8,7 @@
from settings import DEBUG_MODE


class Point:
class Vector:
__slots__ = ("x", "y", "z", "name")

def __init__(self, x, y, z, name=None):
Expand All @@ -25,7 +25,7 @@ def get_point_wrt(self, reference_frame, name=None):
"""
p = np.array([self.x, self.y, self.z, 1])
p = np.matmul(reference_frame, p)
return Point(p[0], p[1], p[2], name)
return Vector(p[0], p[1], p[2], name)

def update_point_wrt(self, reference_frame, z=0):
p = np.array([self.x, self.y, self.z, 1])
Expand All @@ -47,13 +47,14 @@ def vec(self):
return self.x, self.y, self.z

def __repr__(self):
return f"Point(x={self.x:>+8.2f}, y={self.y:>+8.2f}, z={self.z:>+8.2f}, name='{self.name}')"
s = "Vector(x={self.x:>+8.2f}, y={self.y:>+8.2f}, z={self.z:>+8.2f}, name='{self.name}')"
return s

def __str__(self):
return repr(self)

def __eq__(self, other, percent_tol=0.0075):
if not isinstance(other, Point):
if not isinstance(other, Vector):
return False

tol = length(self) * percent_tol
Expand Down Expand Up @@ -197,11 +198,11 @@ def _return_sin_and_cos(theta):

# get vector pointing from point a to point b
def vector_from_to(a, b):
return Point(b.x - a.x, b.y - a.y, b.z - a.z)
return Vector(b.x - a.x, b.y - a.y, b.z - a.z)


def scale(v, d):
return Point(v.x / d, v.y / d, v.z / d)
return Vector(v.x / d, v.y / d, v.z / d)


def dot(a, b):
Expand All @@ -212,23 +213,23 @@ def cross(a, b):
x = a.y * b.z - a.z * b.y
y = a.z * b.x - a.x * b.z
z = a.x * b.y - a.y * b.x
return Point(x, y, z)
return Vector(x, y, z)


def length(v):
return sqrt(dot(v, v))


def add_vectors(a, b):
return Point(a.x + b.x, a.y + b.y, a.z + b.z)
return Vector(a.x + b.x, a.y + b.y, a.z + b.z)


def subtract_vectors(a, b):
return Point(a.x - b.x, a.y - b.y, a.z - b.z)
return Vector(a.x - b.x, a.y - b.y, a.z - b.z)


def scalar_multiply(p, s):
return Point(s * p.x, s * p.y, s * p.z)
return Vector(s * p.x, s * p.y, s * p.z)


def get_unit_vector(v):
Expand Down
4 changes: 2 additions & 2 deletions tests/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ def assert_hexapod_points_equal(
hexapod, correct_body_points, correct_leg_points, description
):
def msg(a, b):
return f"Unequal Points\nexpected: {a}\n....found: {b}\n(case: {description})"
return f"Unequal Vectors\nexpected: {a}\n....found: {b}\n(case: {description})"

for point_a, point_b in zip(correct_body_points, hexapod.body.all_points):
assert point_a.__eq__(point_b, percent_tol=0.0075), msg(point_a, point_b)
Expand All @@ -27,7 +27,7 @@ def msg(a, b):

def assert_two_hexapods_equal(hexapod1, hexapod2, description):
def msg(a, b):
return f"Unequal Points\n1: {a}\n2:{b}\n(case: {description})"
return f"Unequal Vectors\n1: {a}\n2:{b}\n(case: {description})"

for point_a, point_b in zip(hexapod1.body.all_points, hexapod2.body.all_points):
assert point_a.__eq__(point_b, percent_tol=0.0075), msg(point_a, point_b)
Expand Down
Loading

0 comments on commit 9903c16

Please sign in to comment.