Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

tranimate with sequences of SE3 #8

Closed
wants to merge 2 commits into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 16 additions & 2 deletions spatialmath/base/animate.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
import matplotlib.pyplot as plt
from matplotlib import animation
from spatialmath import base
from collections.abc import Iterable


class Animate:
Expand Down Expand Up @@ -57,6 +58,7 @@ def __init__(self, axes=None, dims=None, projection='ortho', labels=('X', 'Y', '
Will setup to plot into an existing or a new Axes3D instance.

"""
self.trajectory = None
self.displaylist = []

if axes is None:
Expand Down Expand Up @@ -104,6 +106,12 @@ def trplot(self, end, start=None, **kwargs):
:seealso: :func:`run`

"""
if not isinstance(end, (np.ndarray, np.generic) ) and isinstance(end, Iterable):
if len(end) == 1:
end = end[0]
elif len(end) >= 2:
self.trajectory = end

# stash the final value
if base.isrot(end):
self.end = base.r2t(end)
Expand All @@ -129,7 +137,7 @@ def run(self, movie=None, axes=None, repeat=False, interval=50, nframes=100, pau
:type axes: Axes3D reference
:param repeat: animate in endless loop [default False]
:type repeat: bool
:param nframes: number of steps in the animation [defaault 100]
:param nframes: number of steps in the animation [default 100]
:type nframes: int
:param interval: number of milliseconds between frames [default 50]
:type interval: int
Expand All @@ -147,7 +155,11 @@ def run(self, movie=None, axes=None, repeat=False, interval=50, nframes=100, pau
"""

def update(frame, a):
T = base.trinterp(start=self.start, end=self.end, s=frame / nframes)
# if contains trajectory:
if self.trajectory is not None:
T = self.trajectory[frame]
else:
T = base.trinterp(start=self.start, end=self.end, s=frame / nframes)
a._draw(T)
if frame == nframes - 1:
a.done = True
Expand All @@ -158,6 +170,8 @@ def update(frame, a):
repeat = False

self.done = False
if self.trajectory is not None:
nframes = len(self.trajectory)
ani = animation.FuncAnimation(fig=plt.gcf(), func=update, frames=range(0, nframes), fargs=(self,), blit=False, interval=interval, repeat=repeat)
if movie is None:
while repeat or not self.done:
Expand Down