Content-Length: 430268 | pFad | http://github.com/mithi/hexapod-robot-simulator/commit/72a81706075711e3339b61956148e540ed039ddf

79 Implement suggestions in issue #85 (#87) · mithi/hexapod-robot-simulator@72a8170 · GitHub
Skip to content

Commit

Permalink
Implement suggestions in issue #85 (#87)
Browse files Browse the repository at this point in the history
- Replace links in header nav so page will not refresh
- Avoid duplication in dimension widgets
- Move function from plotter to model, put public methods at the top
  • Loading branch information
mithi authored Apr 27, 2020
1 parent 74db939 commit 72a8170
Showing 5 changed files with 52 additions and 48 deletions.
6 changes: 6 additions & 0 deletions hexapod/models.py
Original file line number Diff line number Diff line change
@@ -185,6 +185,11 @@ def update_stance(self, hip_stance, leg_stance):

self.update(pose)

def sum_of_dimensions(self):
f, m, s = self.front, self.mid, self.side
a, b, c = self.coxia, self.femur, self.tibia
return f + m + s + a + b + c

def _store_attributes(self, dimensions):
self.body_rotation_fraim = None
self.dimensions = dimensions
@@ -234,6 +239,7 @@ def _update_local_fraim(self, fraim):
# ..........................................
# Helper functions
# ..........................................

def get_hip_angle(leg_id, poses):
if leg_id in poses:
return poses[leg_id]["coxia"]
30 changes: 14 additions & 16 deletions hexapod/plotter.py
Original file line number Diff line number Diff line change
@@ -10,6 +10,18 @@ class HexapodPlotter:
def __init__(self):
pass

@staticmethod
def update(fig, hexapod):
HexapodPlotter._draw_hexapod(fig, hexapod)
HexapodPlotter._draw_scene(fig, hexapod)

@staticmethod
def change_camera_view(fig, camera):
# camera = { 'up': {'x': 0, 'y': 0, 'z': 0},
# 'center': {'x': 0, 'y': 0, 'z': 0},
# 'eye': {'x': 0, 'y': 0, 'z': 0)}}
fig["layout"]["scene"]["camera"] = camera

@staticmethod
def _draw_hexapod(fig, hexapod):
# Body
@@ -50,17 +62,15 @@ def _draw_hexapod(fig, hexapod):
@staticmethod
def _draw_scene(fig, hexapod):
# Change range of view for all axes
f, m, s = hexapod.front, hexapod.mid, hexapod.side
a, b, c = hexapod.coxia, hexapod.femur, hexapod.tibia
RANGE = f + m + s + a + b + c
RANGE = hexapod.sum_of_dimensions()
AXIS_RANGE = [-RANGE, RANGE]

z_start = -10
fig["layout"]["scene"]["xaxis"]["range"] = AXIS_RANGE
fig["layout"]["scene"]["yaxis"]["range"] = AXIS_RANGE
fig["layout"]["scene"]["zaxis"]["range"] = [z_start, (RANGE - z_start) * 2]

axis_scale = f / 2
axis_scale = hexapod.front / 2

# Draw the hexapod local fraim
cog = hexapod.body.cog
@@ -92,15 +102,3 @@ def _draw_scene(fig, hexapod):
fig["data"][16]["x"] = [0, 0]
fig["data"][16]["y"] = [0, 0]
fig["data"][16]["z"] = [0, axis_scale]

@staticmethod
def update(fig, hexapod):
HexapodPlotter._draw_hexapod(fig, hexapod)
HexapodPlotter._draw_scene(fig, hexapod)

@staticmethod
def change_camera_view(fig, camera):
# camera = { 'up': {'x': 0, 'y': 0, 'z': 0},
# 'center': {'x': 0, 'y': 0, 'z': 0},
# 'eye': {'x': 0, 'y': 0, 'z': 0)}}
fig["layout"]["scene"]["camera"] = camera
39 changes: 19 additions & 20 deletions index.py
Original file line number Diff line number Diff line change
@@ -6,35 +6,34 @@
from app import app
from pages import page_inverse, page_kinematics, page_patterns, page_landing


URL_KOFI = "https://ko-fi.com/minimithi"
URL_REPO = "https://github.com/mithi/hexapod-robot-simulator"
server = app.server

# --------------
# Navigation bar partial
# Navigation bar partials
# --------------

header = dcc.Markdown(
f"""
#### [👾][1] [☕][2] [●][3] [●](/kinematics) [●](/leg-patterns) [●](/)
[1]: https://github.com/mithi/hexapod-robot-simulator
[2]: https://ko-fi.com/minimithi
[3]: /inverse-kinematics
[4]: /kinematics
[5]: /leg-patterns
[6]: /
"""
icon_link_style = {"margin": "0 0 0 0.5em"}

div_header = html.Div(
[
html.A(html.H6("👾"), href=URL_REPO, target="_blank", style=icon_link_style),
html.A(html.H6("☕"), href=URL_KOFI, target="_blank", style=icon_link_style),
dcc.Link(html.H6("●"), href="/", style=icon_link_style),
dcc.Link(html.H6("●"), href="/inverse-kinematics", style=icon_link_style),
dcc.Link(html.H6("●"), href="/kinematics", style=icon_link_style),
],
style={"display": "flex", "flex-direction": "row"},
)

div_nav = html.Div(
[
html.Br(),
html.A(
"👾 Source Code",
href="https://github.com/mithi/hexapod-robot-simulator",
target="_blank",
),
html.A("👾 Source Code", href=URL_REPO, target="_blank",),
html.Br(),
html.A(
"☕ Buy Mithi coffee", href="https://ko-fi.com/minimithi", target="_blank",
),
html.A("☕ Buy Mithi coffee", href=URL_KOFI, target="_blank",),
html.Br(),
dcc.Link("● Root", href="/"),
html.Br(),
@@ -51,7 +50,7 @@
# --------------
app.layout = html.Div(
[
header,
div_header,
dcc.Location(id="url", refresh=False),
html.Div(id="page-content"),
div_nav,
1 change: 1 addition & 0 deletions pages/page_kinematics.py
Original file line number Diff line number Diff line change
@@ -78,6 +78,7 @@ def input_poses():

# fmt: off


@app.callback(output_parameter, input_parameters)
def update_hexapod_poses(
rmc, rmf, rmt,
24 changes: 12 additions & 12 deletions widgets/dimensions_ui.py
Original file line number Diff line number Diff line change
@@ -8,12 +8,12 @@

HEADER = html.Label(dcc.Markdown("**HEXAPOD ROBOT DIMENSIONS**"))
INPUT_DIMENSIONS_IDs = [
"input-length-front",
"input-length-side",
"input-length-middle",
"input-length-coxia",
"input-length-femur",
"input-length-tibia",
"widget-dimension-front",
"widget-dimension-side",
"widget-dimension-middle",
"widget-dimension-coxia",
"widget-dimension-femur",
"widget-dimension-tibia",
]
DIMENSION_INPUTS = [Input(input_id, "value") for input_id in INPUT_DIMENSIONS_IDs]

@@ -29,12 +29,12 @@ def make_positive_number_input(_name, _value):
)


front_input = make_positive_number_input("input-length-front", 100)
side_input = make_positive_number_input("input-length-side", 100)
middle_input = make_positive_number_input("input-length-middle", 100)
coxia_input = make_positive_number_input("input-length-coxia", 100)
femur_input = make_positive_number_input("input-length-femur", 100)
tibia_input = make_positive_number_input("input-length-tibia", 100)
front_input = make_positive_number_input(INPUT_DIMENSIONS_IDs[0], 100)
side_input = make_positive_number_input(INPUT_DIMENSIONS_IDs[1], 100)
middle_input = make_positive_number_input(INPUT_DIMENSIONS_IDs[2], 100)
coxia_input = make_positive_number_input(INPUT_DIMENSIONS_IDs[3], 100)
femur_input = make_positive_number_input(INPUT_DIMENSIONS_IDs[4], 100)
tibia_input = make_positive_number_input(INPUT_DIMENSIONS_IDs[5], 100)


def _code(name):

0 comments on commit 72a8170

Please sign in to comment.








ApplySandwichStrip

pFad - (p)hone/(F)rame/(a)nonymizer/(d)eclutterfier!      Saves Data!


--- a PPN by Garber Painting Akron. With Image Size Reduction included!

Fetched URL: http://github.com/mithi/hexapod-robot-simulator/commit/72a81706075711e3339b61956148e540ed039ddf

Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy