Classes | |
| class | TestPose2SLAMExample |
| class | ThreeLinkArm |
Functions | |
| def | compose (*poses) |
| def | delta (g0, g1) |
| def | run_example () |
| def | trajectory (g0, g1, N=20) |
| def | vector3 (x, y, z) |
| def | vee (M) |
Variables | |
| def | Q0 = vector3(0, 0, 0) |
| Q1 = np.radians(vector3(-30, -45, -90)) | |
| Q2 = np.radians(vector3(-90, 90, 0)) | |
GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, Atlanta, Georgia 30332-0415 All Rights Reserved Authors: Frank Dellaert, et al. (see THANKS for the full author list) See LICENSE for the license information Kinematics of three-link manipulator with GTSAM poses and product of exponential maps. Author: Frank Dellaert
| def gtsam.examples.PlanarManipulatorExample.compose | ( | * | poses | ) |
Compose all Pose2 transforms given as arguments from left to right.
Definition at line 35 of file PlanarManipulatorExample.py.
| def gtsam.examples.PlanarManipulatorExample.delta | ( | g0, | |
| g1 | |||
| ) |
Difference between x,y,,theta components of SE(2) poses.
Definition at line 45 of file PlanarManipulatorExample.py.
| def gtsam.examples.PlanarManipulatorExample.run_example | ( | ) |
Use trajectory interpolation and then trajectory tracking a la Murray
to move a 3-link arm on a straight line.
Definition at line 294 of file PlanarManipulatorExample.py.
| def gtsam.examples.PlanarManipulatorExample.trajectory | ( | g0, | |
| g1, | |||
N = 20 |
|||
| ) |
Create an interpolated trajectory in SE(2), treating x,y, and theta separately.
g0 and g1 are the initial and final pose, respectively.
N is the number of *intervals*
Returns N+1 poses
Definition at line 50 of file PlanarManipulatorExample.py.
| def gtsam.examples.PlanarManipulatorExample.vector3 | ( | x, | |
| y, | |||
| z | |||
| ) |
Create 3D double numpy array.
Definition at line 30 of file PlanarManipulatorExample.py.
| def gtsam.examples.PlanarManipulatorExample.vee | ( | M | ) |
Pose2 vee operator.
Definition at line 40 of file PlanarManipulatorExample.py.
| def gtsam.examples.PlanarManipulatorExample.Q0 = vector3(0, 0, 0) |
Definition at line 199 of file PlanarManipulatorExample.py.
| gtsam.examples.PlanarManipulatorExample.Q1 = np.radians(vector3(-30, -45, -90)) |
Definition at line 200 of file PlanarManipulatorExample.py.
| gtsam.examples.PlanarManipulatorExample.Q2 = np.radians(vector3(-90, 90, 0)) |
Definition at line 201 of file PlanarManipulatorExample.py.