Python Bindings¶
By default, the Python bindings will be built for the default Python version for the corresponding ROS distribution ($ROS_PYTHON_VERSION). In order to build for different versions of Python you can specify PYBIND_PYTHON_EXECUTABLE in the additional CMake arguments of your catkin workspace:
catkin config --cmake-args -DPYBIND_PYTHON_EXECUTABLE=/usr/bin/python3
-
class
pyexotica.ArgumentPosition¶ Bases:
pybind11_builtins.pybind11_objectMembers:
ARG0
ARG1
ARG2
ARG3
ARG4
-
ARG0= <ArgumentPosition.ARG0: 0>¶
-
ARG1= <ArgumentPosition.ARG1: 1>¶
-
ARG2= <ArgumentPosition.ARG2: 2>¶
-
ARG3= <ArgumentPosition.ARG3: 3>¶
-
ARG4= <ArgumentPosition.ARG4: 4>¶
-
property
name¶
-
-
class
pyexotica.BaseType¶ Bases:
pybind11_builtins.pybind11_objectMembers:
Fixed
Floating
Planar
-
Fixed= <BaseType.Fixed: 0>¶
-
Floating= <BaseType.Floating: 10>¶
-
Planar= <BaseType.Planar: 20>¶
-
property
name¶
-
-
class
pyexotica.BoxQPSolution¶ Bases:
pybind11_builtins.pybind11_object-
property
Hff_inv¶
-
property
clamped_idx¶
-
property
free_idx¶
-
property
x¶
-
property
-
class
pyexotica.CollisionProxy¶ Bases:
pybind11_builtins.pybind11_object-
property
contact_1¶
-
property
contact_2¶
-
property
distance¶
-
property
normal_1¶
-
property
normal_2¶
-
property
object_1¶
-
property
object_2¶
-
property
transform_1¶
-
property
transform_2¶
-
property
-
class
pyexotica.CollisionScene¶ Bases:
pybind11_builtins.pybind11_object-
property
always_externally_updated_collision_scene¶
-
continuous_collision_check(self: pyexotica._pyexotica.CollisionScene, arg0: str, arg1: pyexotica._pyexotica.KDLFrame, arg2: pyexotica._pyexotica.KDLFrame, arg3: str, arg4: pyexotica._pyexotica.KDLFrame, arg5: pyexotica._pyexotica.KDLFrame) → pyexotica._pyexotica.ContinuousCollisionProxy¶
-
get_robot_to_robot_collision_distance(self: pyexotica._pyexotica.CollisionScene, arg0: float) → List[pyexotica._pyexotica.CollisionProxy]¶
-
get_robot_to_world_collision_distance(self: pyexotica._pyexotica.CollisionScene, arg0: float) → List[pyexotica._pyexotica.CollisionProxy]¶
-
get_translation(self: pyexotica._pyexotica.CollisionScene, arg0: str) → numpy.ndarray[numpy.float64[3, 1]]¶
-
property
replace_cylinders_with_capsules¶
-
property
replace_primitive_shapes_with_meshes¶
-
property
robot_link_padding¶
-
property
robot_link_scale¶
-
update_collision_object_transforms(self: pyexotica._pyexotica.CollisionScene) → None¶
-
property
world_link_padding¶
-
property
world_link_scale¶
-
property
-
class
pyexotica.Cone¶ Bases:
pyexotica._pyexotica.Shape-
property
length¶
-
name= 'cone'¶
-
property
radius¶
-
property
-
class
pyexotica.ContinuousCollisionProxy¶ Bases:
pybind11_builtins.pybind11_object-
property
contact_transform_1¶
-
property
contact_transform_2¶
-
property
in_collision¶
-
property
object_1¶
-
property
object_2¶
-
property
time_of_contact¶
-
property
transform_1¶
-
property
transform_2¶
-
property
-
class
pyexotica.ControlCostLossTermType¶ Bases:
pybind11_builtins.pybind11_objectMembers:
Undefined
L2
SmoothL1
Huber
PseudoHuber
-
Huber= <ControlCostLossTermType.Huber: 2>¶
-
L2= <ControlCostLossTermType.L2: 0>¶
-
PseudoHuber= <ControlCostLossTermType.PseudoHuber: 3>¶
-
SmoothL1= <ControlCostLossTermType.SmoothL1: 1>¶
-
Undefined= <ControlCostLossTermType.Undefined: -1>¶
-
property
name¶
-
-
class
pyexotica.Cylinder¶ Bases:
pyexotica._pyexotica.Shape-
property
length¶
-
name= 'cylinder'¶
-
property
radius¶
-
property
-
class
pyexotica.DynamicsSolver¶ Bases:
pyexotica._pyexotica.Object-
F(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, 1]]¶
-
compute_derivatives(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → None¶
-
property
dt¶
-
f(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, 1]]¶
-
fu(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, n]]¶
-
fu_fd(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, n]]¶
-
fx(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, n]]¶
-
fx_fd(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_Fu(self: pyexotica._pyexotica.DynamicsSolver) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_Fx(self: pyexotica._pyexotica.DynamicsSolver) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_fu(self: pyexotica._pyexotica.DynamicsSolver) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_fx(self: pyexotica._pyexotica.DynamicsSolver) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_position(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, 1]]¶
-
property
has_second_order_derivatives¶
-
integrate(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]], arg2: float) → numpy.ndarray[numpy.float64[m, 1]]¶
-
property
integrator¶
-
property
ndx¶
-
property
nq¶
-
property
nu¶
-
property
nv¶
-
property
nx¶
-
simulate(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]], arg2: float) → numpy.ndarray[numpy.float64[m, 1]]¶
-
state_delta(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]]) → numpy.ndarray[numpy.float64[m, 1]]¶
-
state_delta_derivative(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]], arg2: exotica::ArgumentPosition) → numpy.ndarray[numpy.float64[m, n]]¶
-
state_delta_second_derivative(self: pyexotica._pyexotica.DynamicsSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, 1]], arg2: exotica::ArgumentPosition) → Hessian¶
-
-
class
pyexotica.EndPoseTask¶ Bases:
pybind11_builtins.pybind11_object-
property
Phi¶
-
property
S¶
-
get_S(self: pyexotica._pyexotica.EndPoseTask, arg0: str) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_goal(self: pyexotica._pyexotica.EndPoseTask, arg0: str) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_rho(self: pyexotica._pyexotica.EndPoseTask, arg0: str) → float¶
-
get_task_error(self: pyexotica._pyexotica.EndPoseTask, arg0: str) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_task_jacobian(self: pyexotica._pyexotica.EndPoseTask, arg0: str) → numpy.ndarray[numpy.float64[m, n]]¶
-
property
jacobian¶
-
property
length_Phi¶
-
property
length_jacobian¶
-
property
num_tasks¶
-
set_goal(self: pyexotica._pyexotica.EndPoseTask, arg0: str, arg1: numpy.ndarray[numpy.float64[m, 1]]) → None¶
-
set_rho(self: pyexotica._pyexotica.EndPoseTask, arg0: str, arg1: float) → None¶
-
property
task_maps¶
-
property
tasks¶
-
property
y¶
-
property
ydiff¶
-
property
-
class
pyexotica.FeedbackMotionSolver¶ Bases:
pyexotica._pyexotica.MotionSolver-
get_feedback_control(self: pyexotica._pyexotica.FeedbackMotionSolver, arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: int) → numpy.ndarray[numpy.float64[m, 1]]¶
-
-
class
pyexotica.Integrator¶ Bases:
pybind11_builtins.pybind11_objectMembers:
RK1
SymplecticEuler
RK2
RK4
-
RK1= <Integrator.RK1: 0>¶
-
RK2= <Integrator.RK2: 2>¶
-
RK4= <Integrator.RK4: 3>¶
-
SymplecticEuler= <Integrator.SymplecticEuler: 1>¶
-
property
name¶
-
-
class
pyexotica.InteractiveCostTuning(problem)¶ Bases:
object-
mainloop()¶ Starts tk mainloop.
Quits interactive cost tuning.
Resets entries/exotica to original cost terms as specified in xml.
Saves current rho parameters in entries to file in home dir.
Sets rho parameters in entries into Exotica problem.
-
-
class
pyexotica.KDLFrame¶ Bases:
pybind11_builtins.pybind11_object-
static
diff(arg0: pyexotica._pyexotica.KDLFrame, arg1: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_angle_axis(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_frame(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_quaternion(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_rpy(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_translation(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[3, 1]]¶
-
get_translation_and_angle_axis(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_translation_and_quaternion(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_translation_and_rpy(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_translation_and_zyx(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_translation_and_zyz(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_zyx(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_zyz(self: pyexotica._pyexotica.KDLFrame) → numpy.ndarray[numpy.float64[m, 1]]¶
-
static
interpolate(arg0: pyexotica._pyexotica.KDLFrame, arg1: pyexotica._pyexotica.KDLFrame, arg2: float) → pyexotica._pyexotica.KDLFrame¶
-
inverse(self: pyexotica._pyexotica.KDLFrame) → pyexotica._pyexotica.KDLFrame¶
-
property
p¶
-
static
-
class
pyexotica.KDLRigidBodyInertia¶ Bases:
pybind11_builtins.pybind11_object-
static
Zero() → pyexotica._pyexotica.KDLRigidBodyInertia¶
-
static
-
class
pyexotica.KDLRotationalInertia¶ Bases:
pybind11_builtins.pybind11_object-
static
Zero() → pyexotica._pyexotica.KDLRotationalInertia¶
-
static
-
class
pyexotica.KDLVector¶ Bases:
pybind11_builtins.pybind11_object-
static
Zero() → pyexotica._pyexotica.KDLVector¶
-
x(self: pyexotica._pyexotica.KDLVector) → float¶
-
y(self: pyexotica._pyexotica.KDLVector) → float¶
-
z(self: pyexotica._pyexotica.KDLVector) → float¶
-
static
-
class
pyexotica.Mesh¶ Bases:
pyexotica._pyexotica.Shape-
computeTriangleNormals(self: pyexotica._pyexotica.Mesh) → None¶
-
computeVertexNormals(self: pyexotica._pyexotica.Mesh) → None¶
-
mergeVertices(self: pyexotica._pyexotica.Mesh, arg0: float) → None¶
-
property
triangle_count¶
-
property
vertex_count¶
-
-
class
pyexotica.MotionSolver¶ Bases:
pyexotica._pyexotica.Object-
get_planning_time(self: pyexotica._pyexotica.MotionSolver) → float¶
-
get_problem(self: pyexotica._pyexotica.MotionSolver) → exotica::PlanningProblem¶
-
property
max_iterations¶
-
solve(self: pyexotica._pyexotica.MotionSolver) → numpy.ndarray[numpy.float64[m, n]]¶ Solve the problem
-
specify_problem(self: pyexotica._pyexotica.MotionSolver, planning_problem: exotica::PlanningProblem) → None¶ Assign problem to the solver
-
-
class
pyexotica.Object¶ Bases:
pybind11_builtins.pybind11_object-
property
debug_mode¶
-
property
name¶ Object name
-
property
namespace¶
-
property
type¶ Object type
-
property
-
class
pyexotica.OcTree¶ Bases:
pyexotica._pyexotica.Shape
-
class
pyexotica.Plane¶ Bases:
pyexotica._pyexotica.Shape-
property
a¶
-
property
b¶
-
property
c¶
-
property
d¶
-
isFixed(self: pyexotica._pyexotica.Plane) → bool¶
-
name= 'plane'¶
-
property
-
class
pyexotica.PlanningProblem¶ Bases:
pyexotica._pyexotica.Object-
property
N¶
-
apply_start_state(self: pyexotica._pyexotica.PlanningProblem, arg0: bool) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_cost_evolution(self: pyexotica._pyexotica.PlanningProblem) → Tuple[List[float], List[float]]¶
-
get_number_of_iterations(self: pyexotica._pyexotica.PlanningProblem) → int¶
-
get_number_of_problem_updates(self: pyexotica._pyexotica.PlanningProblem) → int¶
-
get_scene(self: pyexotica._pyexotica.PlanningProblem) → exotica::Scene¶
-
get_task_maps(self: pyexotica._pyexotica.PlanningProblem) → Dict[str, pyexotica._pyexotica.TaskMap]¶
-
get_tasks(self: pyexotica._pyexotica.PlanningProblem) → List[pyexotica._pyexotica.TaskMap]¶
-
is_valid(self: pyexotica._pyexotica.PlanningProblem) → bool¶
-
property
num_controls¶
-
property
num_positions¶
-
property
num_velocities¶
-
pre_update(self: pyexotica._pyexotica.PlanningProblem) → None¶
-
reset_number_of_problem_updates(self: pyexotica._pyexotica.PlanningProblem) → None¶
-
property
start_state¶
-
property
start_time¶
-
property
termination_criterion¶
-
property
-
class
pyexotica.RotationType¶ Bases:
pybind11_builtins.pybind11_objectMembers:
Quaternion
RPY
ZYZ
ZYX
AngleAxis
Matrix
-
AngleAxis= <RotationType.AngleAxis: 4>¶
-
Matrix= <RotationType.Matrix: 5>¶
-
Quaternion= <RotationType.Quaternion: 0>¶
-
RPY= <RotationType.RPY: 1>¶
-
ZYX= <RotationType.ZYX: 2>¶
-
ZYZ= <RotationType.ZYZ: 3>¶
-
property
name¶
-
-
class
pyexotica.SamplingTask¶ Bases:
pybind11_builtins.pybind11_object-
property
Phi¶
-
property
S¶
-
get_goal(self: pyexotica._pyexotica.SamplingTask, arg0: str) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_rho(self: pyexotica._pyexotica.SamplingTask, arg0: str) → float¶
-
property
length_Phi¶
-
property
length_jacobian¶
-
property
num_tasks¶
-
set_goal(self: pyexotica._pyexotica.SamplingTask, arg0: str, arg1: numpy.ndarray[numpy.float64[m, 1]]) → None¶
-
set_rho(self: pyexotica._pyexotica.SamplingTask, arg0: str, arg1: float) → None¶
-
property
task_maps¶
-
property
tasks¶
-
property
y¶
-
property
ydiff¶
-
property
-
class
pyexotica.Scene¶ Bases:
pyexotica._pyexotica.Object-
add_object(*args, **kwargs)¶ Overloaded function.
add_object(self: pyexotica._pyexotica.Scene, name: str, transform: pyexotica._pyexotica.KDLFrame = KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), parent: str = ‘’, shape_resource_path: str, scale: numpy.ndarray[numpy.float64[3, 1]] = array([1., 1., 1.]), color: numpy.ndarray[numpy.float64[4, 1]] = array([0.5, 0.5, 0.5, 1. ]), update_collision_scene: bool = True) -> None
add_object(self: pyexotica._pyexotica.Scene, name: str, transform: pyexotica._pyexotica.KDLFrame = KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), parent: str = ‘’, shape: shapes::Shape, inertia: pyexotica._pyexotica.KDLRigidBodyInertia = <pyexotica._pyexotica.KDLRigidBodyInertia object at 0x7fe4180c32f0>, color: numpy.ndarray[numpy.float64[4, 1]] = array([0.5, 0.5, 0.5, 1. ]), update_collision_scene: bool = True) -> None
-
add_object_to_environment(self: pyexotica._pyexotica.Scene, name: str, transform: pyexotica._pyexotica.KDLFrame = KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), shape: shapes::Shape, color: numpy.ndarray[numpy.float64[4, 1]] = array([0.5, 0.5, 0.5, 1. ]), update_collision_scene: bool = True) → None¶
-
add_trajectory(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str) → None¶
-
add_trajectory_from_array(self: pyexotica._pyexotica.Scene, link: str, data: numpy.ndarray[numpy.float64[m, n]], radius: float) → None¶
-
add_trajectory_from_file(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str) → None¶
-
attach_object(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str) → None¶
-
attach_object_local(*args, **kwargs)¶ Overloaded function.
attach_object_local(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str, arg2: pyexotica._pyexotica.KDLFrame) -> None
attach_object_local(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str, arg2: numpy.ndarray[numpy.float64[m, 1]]) -> None
-
clean_scene(self: pyexotica._pyexotica.Scene) → None¶
-
property
controlled_joint_to_collision_link_map¶
-
detach_object(self: pyexotica._pyexotica.Scene, arg0: str) → None¶
-
fk(*args, **kwargs)¶ Overloaded function.
fk(self: pyexotica._pyexotica.Scene, arg0: str, arg1: pyexotica._pyexotica.KDLFrame, arg2: str, arg3: pyexotica._pyexotica.KDLFrame) -> pyexotica._pyexotica.KDLFrame
fk(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str) -> pyexotica._pyexotica.KDLFrame
fk(self: pyexotica._pyexotica.Scene, arg0: str) -> pyexotica._pyexotica.KDLFrame
-
get_collision_distance(*args, **kwargs)¶ Overloaded function.
get_collision_distance(self: pyexotica._pyexotica.Scene, check_self_collision: bool = True) -> List[pyexotica._pyexotica.CollisionProxy]
get_collision_distance(self: pyexotica._pyexotica.Scene, object_1: str, object_2: str) -> List[pyexotica._pyexotica.CollisionProxy]
get_collision_distance(self: pyexotica._pyexotica.Scene, object_1: str, check_self_collision: bool = True) -> List[pyexotica._pyexotica.CollisionProxy]
get_collision_distance(self: pyexotica._pyexotica.Scene, objects: List[str], check_self_collision: bool = True) -> List[pyexotica._pyexotica.CollisionProxy]
-
get_collision_robot_links(self: pyexotica._pyexotica.Scene) → List[str]¶
-
get_collision_scene(self: pyexotica._pyexotica.Scene) → exotica::CollisionScene¶
-
get_collision_world_links(self: pyexotica._pyexotica.Scene) → List[str]¶
-
get_controlled_joint_names(self: pyexotica._pyexotica.Scene) → List[str]¶
-
get_controlled_link_names(self: pyexotica._pyexotica.Scene) → List[str]¶
-
get_controlled_state(self: pyexotica._pyexotica.Scene) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_dynamics_solver(self: pyexotica._pyexotica.Scene) → exotica::AbstractDynamicsSolver<double, -1, -1>¶
-
get_kinematic_tree(self: pyexotica._pyexotica.Scene) → exotica::KinematicTree¶
-
get_model_joint_names(self: pyexotica._pyexotica.Scene) → List[str]¶
-
get_model_link_names(self: pyexotica._pyexotica.Scene) → List[str]¶
-
get_model_state(self: pyexotica._pyexotica.Scene) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_model_state_map(self: pyexotica._pyexotica.Scene) → Dict[str, float]¶
-
get_root_frame_name(self: pyexotica._pyexotica.Scene) → str¶
-
get_root_joint_name(self: pyexotica._pyexotica.Scene) → str¶
-
get_scene(self: pyexotica._pyexotica.Scene) → str¶
-
get_trajectory(self: pyexotica._pyexotica.Scene, arg0: str) → str¶
-
get_tree_names(self: pyexotica._pyexotica.Scene) → List[str]¶
-
has_attached_object(self: pyexotica._pyexotica.Scene, arg0: str) → bool¶
-
property
has_quaternion_floating_base¶
-
hessian(*args, **kwargs)¶ Overloaded function.
hessian(self: pyexotica._pyexotica.Scene, arg0: str, arg1: pyexotica._pyexotica.KDLFrame, arg2: str, arg3: pyexotica._pyexotica.KDLFrame) -> Hessian
hessian(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str) -> Hessian
hessian(self: pyexotica._pyexotica.Scene, arg0: str) -> Hessian
-
is_allowed_to_collide(self: pyexotica._pyexotica.Scene, object_1: str, object_2: str, check_self_collision: bool = True) → bool¶
-
is_collision_free(self: pyexotica._pyexotica.Scene, object_1: str, object_2: str, safe_distance: float = 0.0) → bool¶
-
is_state_valid(self: pyexotica._pyexotica.Scene, check_self_collision: bool = True, safe_distance: float = 0.0) → bool¶
-
jacobian(*args, **kwargs)¶ Overloaded function.
jacobian(self: pyexotica._pyexotica.Scene, arg0: str, arg1: pyexotica._pyexotica.KDLFrame, arg2: str, arg3: pyexotica._pyexotica.KDLFrame) -> numpy.ndarray[numpy.float64[m, n]]
jacobian(self: pyexotica._pyexotica.Scene, arg0: str, arg1: str) -> numpy.ndarray[numpy.float64[m, n]]
jacobian(self: pyexotica._pyexotica.Scene, arg0: str) -> numpy.ndarray[numpy.float64[m, n]]
-
load_scene(self: pyexotica._pyexotica.Scene, scene_string: str, offset_transform: pyexotica._pyexotica.KDLFrame = KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), update_collision_scene: bool = True) → None¶
-
load_scene_file(self: pyexotica._pyexotica.Scene, file_name: str, offset_transform: pyexotica._pyexotica.KDLFrame = KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), update_collision_scene: bool = True) → None¶
-
property
model_link_to_collision_link_map¶
-
property
num_controls¶
-
property
num_positions¶
-
property
num_state¶
-
property
num_state_derivative¶
-
property
num_velocities¶
-
publish_proxies(self: pyexotica._pyexotica.Scene, arg0: List[pyexotica._pyexotica.CollisionProxy]) → None¶
-
publish_scene(self: pyexotica._pyexotica.Scene) → None¶
-
remove_object(self: pyexotica._pyexotica.Scene, arg0: str) → None¶
-
remove_trajectory(self: pyexotica._pyexotica.Scene, arg0: str) → None¶
-
set_model_state(self: pyexotica._pyexotica.Scene, x: numpy.ndarray[numpy.float64[m, 1]], t: float = 0.0, update_trajectory: bool = False) → None¶
-
set_model_state_map(self: pyexotica._pyexotica.Scene, x: Dict[str, float], t: float = 0.0, update_trajectory: bool = False) → None¶
-
update(self: pyexotica._pyexotica.Scene, x: numpy.ndarray[numpy.float64[m, 1]], t: float = 0.0) → None¶
-
update_collision_objects(self: pyexotica._pyexotica.Scene) → None¶
-
update_planning_scene(self: pyexotica._pyexotica.Scene, arg0: genpy.Message) → None¶
-
update_planning_scene_world(self: pyexotica._pyexotica.Scene, arg0: genpy.Message) → None¶
-
update_scene_frames(self: pyexotica._pyexotica.Scene) → None¶
-
property
world_links_to_exclude_from_collision_scene¶
-
-
class
pyexotica.Setup¶ Bases:
pybind11_builtins.pybind11_object-
static
create_dynamics_solver(arg0: Initializer) → exotica::AbstractDynamicsSolver<double, -1, -1>¶
-
static
create_problem(arg0: Initializer) → exotica::PlanningProblem¶
-
static
create_scene(arg0: Initializer) → exotica::Scene¶
-
static
create_solver(arg0: Initializer) → exotica::MotionSolver¶
-
static
get_collision_scenes() → List[str]¶ Returns a list of available collision scene plug-ins.
-
static
get_dynamics_solvers() → List[str]¶ Returns a list of available dynamics solvers plug-ins.
-
static
get_initializers() → List[Initializer]¶ Returns a list of available initializers with all available parameters/arguments.
-
static
get_maps() → List[str]¶ Returns a list of available task maps.
-
static
get_package_path(arg0: str) → str¶ ROS package path resolution.
-
static
get_problems() → List[str]¶ Returns a list of available problems.
-
static
get_solvers() → List[str]¶ Returns a list of available solvers.
-
static
init_ros(name: str = 'exotica', anonymous: bool = False) → None¶ Initializes an internal ROS node for publishing debug information from Exotica (i.e., activates ROS features). Options are setting the name and whether to spawn an anonymous node.
-
static
load_problem(filepath: str) → exotica::PlanningProblem¶ Instantiate only a problem from an XML file containing solely a problem initializer.
-
static
load_solver(filepath: str) → exotica::MotionSolver¶ Instantiate solver and problem from an XML file containing both a solver and problem initializer.
-
static
load_solver_standalone(filepath: str) → exotica::MotionSolver¶ Instantiate only a solver from an XML file containing solely a solver initializer.
-
static
print_supported_classes() → None¶ Print a list of available plug-ins sorted by class.
-
static
-
class
pyexotica.Shape¶ Bases:
pybind11_builtins.pybind11_object-
isFixed(self: pyexotica._pyexotica.Shape) → bool¶
-
padd(self: pyexotica._pyexotica.Shape, arg0: float) → None¶
-
scale(self: pyexotica._pyexotica.Shape, arg0: float) → None¶
-
scaleAndPadd(self: pyexotica._pyexotica.Shape, arg0: float, arg1: float) → None¶
-
property
type¶
-
-
class
pyexotica.ShapeType¶ Bases:
pybind11_builtins.pybind11_objectMembers:
UNKNOWN_SHAPE
SPHERE
CYLINDER
CONE
BOX
PLANE
MESH
OCTREE
-
BOX= <ShapeType.BOX: 4>¶
-
CONE= <ShapeType.CONE: 3>¶
-
CYLINDER= <ShapeType.CYLINDER: 2>¶
-
MESH= <ShapeType.MESH: 6>¶
-
OCTREE= <ShapeType.OCTREE: 7>¶
-
PLANE= <ShapeType.PLANE: 5>¶
-
SPHERE= <ShapeType.SPHERE: 1>¶
-
UNKNOWN_SHAPE= <ShapeType.UNKNOWN_SHAPE: 0>¶
-
property
name¶
-
-
class
pyexotica.TaskIndexing¶ Bases:
pybind11_builtins.pybind11_object-
property
id¶
-
property
length¶
-
property
lengthJ¶
-
property
start¶
-
property
startJ¶
-
property
-
class
pyexotica.TaskMap¶ Bases:
pyexotica._pyexotica.Object-
property
id¶
-
property
length¶
-
property
lengthJ¶
-
property
start¶
-
property
startJ¶
-
task_space_dim(self: pyexotica._pyexotica.TaskMap) → int¶
-
task_space_jacobian_dim(self: pyexotica._pyexotica.TaskMap) → int¶
-
property
-
class
pyexotica.TaskSpaceVector¶ Bases:
pybind11_builtins.pybind11_object-
property
data¶
-
set_zero(self: pyexotica._pyexotica.TaskSpaceVector, arg0: int) → None¶
-
property
-
class
pyexotica.TerminationCriterion¶ Bases:
pybind11_builtins.pybind11_objectMembers:
NotStarted
IterationLimit
BacktrackIterationLimit
StepTolerance
FunctionTolerance
GradientTolerance
Divergence
UserDefined
Convergence
-
BacktrackIterationLimit= <TerminationCriterion.BacktrackIterationLimit: 1>¶
-
Convergence= <TerminationCriterion.Convergence: 7>¶
-
Divergence= <TerminationCriterion.Divergence: 5>¶
-
FunctionTolerance= <TerminationCriterion.FunctionTolerance: 3>¶
-
GradientTolerance= <TerminationCriterion.GradientTolerance: 4>¶
-
IterationLimit= <TerminationCriterion.IterationLimit: 0>¶
-
NotStarted= <TerminationCriterion.NotStarted: -1>¶
-
StepTolerance= <TerminationCriterion.StepTolerance: 2>¶
-
UserDefined= <TerminationCriterion.UserDefined: 6>¶
-
property
name¶
-
-
class
pyexotica.TimeIndexedTask¶ Bases:
pybind11_builtins.pybind11_object-
property
Phi¶
-
property
S¶
-
property
T¶
-
property
dPhi_du¶
-
property
dPhi_dx¶
-
property
ddPhi_ddu¶
-
property
ddPhi_ddx¶
-
property
ddPhi_dxdu¶
-
get_S(self: pyexotica._pyexotica.TimeIndexedTask, arg0: str, arg1: int) → numpy.ndarray[numpy.float64[m, n]]¶
-
get_goal(self: pyexotica._pyexotica.TimeIndexedTask, arg0: str, arg1: int) → numpy.ndarray[numpy.float64[m, 1]]¶
-
get_rho(self: pyexotica._pyexotica.TimeIndexedTask, arg0: str, arg1: int) → float¶
-
get_task_error(self: pyexotica._pyexotica.TimeIndexedTask, arg0: str, arg1: int) → numpy.ndarray[numpy.float64[m, 1]]¶
-
property
hessian¶
-
property
indexing¶
-
property
jacobian¶
-
property
length_Phi¶
-
property
length_jacobian¶
-
property
num_tasks¶
-
property
rho¶
-
set_goal(self: pyexotica._pyexotica.TimeIndexedTask, arg0: str, arg1: numpy.ndarray[numpy.float64[m, 1]], arg2: int) → None¶
-
set_rho(self: pyexotica._pyexotica.TimeIndexedTask, arg0: str, arg1: float, arg2: int) → None¶
-
property
task_maps¶
-
property
tasks¶
-
property
y¶
-
property
ydiff¶
-
property
-
class
pyexotica.Timer¶ Bases:
pybind11_builtins.pybind11_object-
get_duration(self: pyexotica._pyexotica.Timer) → float¶
-
reset(self: pyexotica._pyexotica.Timer) → None¶
-
-
class
pyexotica.VisualizationMeshcat¶ Bases:
pybind11_builtins.pybind11_object-
delete(self: pyexotica._pyexotica.VisualizationMeshcat, path: str = '') → None¶
-
display_scene(self: pyexotica._pyexotica.VisualizationMeshcat, use_mesh_materials: bool = True) → None¶
-
display_state(self: pyexotica._pyexotica.VisualizationMeshcat, state: numpy.ndarray[numpy.float64[m, 1]], t: float = 0.0) → None¶
-
display_trajectory(self: pyexotica._pyexotica.VisualizationMeshcat, trajectory: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous], dt: float = 1.0) → None¶
-
get_file_url(self: pyexotica._pyexotica.VisualizationMeshcat) → str¶
-
get_web_url(self: pyexotica._pyexotica.VisualizationMeshcat) → str¶
-
set_property(*args, **kwargs)¶ Overloaded function.
set_property(self: pyexotica._pyexotica.VisualizationMeshcat, path: str, property: str, value: float) -> None
set_property(self: pyexotica._pyexotica.VisualizationMeshcat, path: str, property: str, value: str) -> None
set_property(self: pyexotica._pyexotica.VisualizationMeshcat, path: str, property: str, value: bool) -> None
set_property(self: pyexotica._pyexotica.VisualizationMeshcat, path: str, property: str, value: numpy.ndarray[numpy.float64[3, 1]]) -> None
set_property(self: pyexotica._pyexotica.VisualizationMeshcat, path: str, property: str, value: numpy.ndarray[numpy.float64[4, 1]]) -> None
-
-
class
pyexotica.VisualizationMoveIt¶ Bases:
pybind11_builtins.pybind11_object-
display_trajectory(self: pyexotica._pyexotica.VisualizationMoveIt, arg0: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous]) → None¶
-
-
pyexotica.box_qp(H: numpy.ndarray[numpy.float64[m, n]], q: numpy.ndarray[numpy.float64[m, 1]], b_low: numpy.ndarray[numpy.float64[m, 1]], b_high: numpy.ndarray[numpy.float64[m, 1]], x_init: numpy.ndarray[numpy.float64[m, 1]], gamma: float, max_iterations: int, epsilon: float, lambda: float, use_polynomial_linesearch: bool = True, use_cholesky_factorization: bool = True) → pyexotica._pyexotica.BoxQPSolution¶
-
pyexotica.box_qp_old(H: numpy.ndarray[numpy.float64[m, n]], q: numpy.ndarray[numpy.float64[m, 1]], b_low: numpy.ndarray[numpy.float64[m, 1]], b_high: numpy.ndarray[numpy.float64[m, 1]], x_init: numpy.ndarray[numpy.float64[m, 1]], gamma: float, max_iterations: int, epsilon: float, lambda: float, use_polynomial_linesearch: bool = False, use_cholesky_factorization: bool = False) → pyexotica._pyexotica.BoxQPSolution¶
-
pyexotica.check_dynamics_solver_derivatives(name, urdf=None, srdf=None, joint_group=None, additional_args=None, do_test_integrators=True)¶
-
pyexotica.check_trajectory_continuous_time(scene, trajectory)¶
-
pyexotica.check_whether_trajectory_is_collision_free_by_subsampling(scene, trajectory, num_subsamples=10, debug=False)¶ num_subsamples specifies how many steps are checked between two configurations. Returns True if trajectory is collision-free, and False otherwise.
TODO: Support setting time for Scene update.
-
pyexotica.get_colliding_links(scene, margin=0.0, safe_distance=0.0, check_self_collision=True, debug=False)¶
-
pyexotica.plot(solution, labels=None, yscale=None)¶
-
pyexotica.plot_task_cost_over_time(problem)¶ Plots the task cost (task maps) over time given a problem.
-
pyexotica.publish_pose(q, problem, t=0.0)¶
-
pyexotica.publish_time_indexed_trajectory(traj, Ts, problem, once=False)¶
-
pyexotica.publish_trajectory(traj, T, problem, once=False)¶
-
pyexotica.show(url, height=50)¶
-
pyexotica.sig_int_handler(signal, frame)¶
Exotica wrapper of OMPL solvers
-
class
exotica_ompl_solver_py.BKPIECESolver¶
-
class
exotica_ompl_solver_py.ESTSolver¶
-
class
exotica_ompl_solver_py.KPIECESolver¶
-
class
exotica_ompl_solver_py.LazyPRMSolver¶ Bases:
exotica_ompl_solver_py.OMPLMotionSolver-
clear(self: exotica_ompl_solver_py.LazyPRMSolver) → None¶
-
clear_query(self: exotica_ompl_solver_py.LazyPRMSolver) → None¶
-
edge_count(self: exotica_ompl_solver_py.LazyPRMSolver) → int¶
-
milestone_count(self: exotica_ompl_solver_py.LazyPRMSolver) → int¶
-
property
multi_query¶
-
setup(self: exotica_ompl_solver_py.LazyPRMSolver) → None¶
-
-
class
exotica_ompl_solver_py.OMPLMotionSolver¶ Bases:
pyexotica._pyexotica.MotionSolver-
GetRandomSeed(self: exotica_ompl_solver_py.OMPLMotionSolver) → int¶
-
property
longest_valid_segment_length¶
-
property
maximum_extent¶
-
property
valid_segment_count_factor¶
-
-
class
exotica_ompl_solver_py.PRMSolver¶ Bases:
exotica_ompl_solver_py.OMPLMotionSolver-
clear(self: exotica_ompl_solver_py.PRMSolver) → None¶
-
clear_query(self: exotica_ompl_solver_py.PRMSolver) → None¶
-
edge_count(self: exotica_ompl_solver_py.PRMSolver) → int¶
-
expand_roadmap(self: exotica_ompl_solver_py.PRMSolver, arg0: float) → None¶
-
grow_roadmap(self: exotica_ompl_solver_py.PRMSolver, arg0: float) → None¶
-
milestone_count(self: exotica_ompl_solver_py.PRMSolver) → int¶
-
property
multi_query¶
-
setup(self: exotica_ompl_solver_py.PRMSolver) → None¶
-
-
class
exotica_ompl_solver_py.RRTConnectSolver¶ Bases:
exotica_ompl_solver_py.OMPLMotionSolver-
property
range¶
-
property
-
class
exotica_ompl_solver_py.RRTSolver¶
Exotica task map definitions
-
class
exotica_core_task_maps_py.CenterOfMass¶ Bases:
pyexotica._pyexotica.TaskMap
-
class
exotica_core_task_maps_py.CollisionDistance¶ Bases:
pyexotica._pyexotica.TaskMap-
get_collision_proxies(self: exotica_core_task_maps_py.CollisionDistance) → List[pyexotica._pyexotica.CollisionProxy]¶
-
-
class
exotica_core_task_maps_py.ControlRegularization¶ Bases:
pyexotica._pyexotica.TaskMap-
property
joint_map¶
-
property
joint_ref¶
-
property
-
class
exotica_core_task_maps_py.Distance¶ Bases:
pyexotica._pyexotica.TaskMap
-
class
exotica_core_task_maps_py.EffAxisAlignment¶ Bases:
pyexotica._pyexotica.TaskMap-
get_axis(self: exotica_core_task_maps_py.EffAxisAlignment, arg0: str) → numpy.ndarray[numpy.float64[3, 1]]¶
-
get_direction(self: exotica_core_task_maps_py.EffAxisAlignment, arg0: str) → numpy.ndarray[numpy.float64[3, 1]]¶
-
set_axis(self: exotica_core_task_maps_py.EffAxisAlignment, arg0: str, arg1: numpy.ndarray[numpy.float64[3, 1]]) → None¶
-
set_direction(self: exotica_core_task_maps_py.EffAxisAlignment, arg0: str, arg1: numpy.ndarray[numpy.float64[3, 1]]) → None¶
-
-
class
exotica_core_task_maps_py.EffBox¶ Bases:
pyexotica._pyexotica.TaskMap-
get_lower_limit(self: exotica_core_task_maps_py.EffBox, arg0: int) → numpy.ndarray[numpy.float64[3, 1]]¶
-
get_upper_limit(self: exotica_core_task_maps_py.EffBox, arg0: int) → numpy.ndarray[numpy.float64[3, 1]]¶
-
-
class
exotica_core_task_maps_py.EffFrame¶ Bases:
pyexotica._pyexotica.TaskMap-
property
rotation_type¶
-
property
-
class
exotica_core_task_maps_py.EffOrientation¶ Bases:
pyexotica._pyexotica.TaskMap-
property
rotation_type¶
-
property
-
class
exotica_core_task_maps_py.EffPosition¶ Bases:
pyexotica._pyexotica.TaskMap
-
class
exotica_core_task_maps_py.InteractionMesh¶ Bases:
pyexotica._pyexotica.TaskMap-
property
W¶
-
static
compute_goal_laplace(arg0: List[pyexotica._pyexotica.KDLFrame], arg1: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous]) → numpy.ndarray[numpy.float64[m, 1]]¶
-
static
compute_laplace(arg0: numpy.ndarray[numpy.float64[m, 1]], arg1: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous]) → numpy.ndarray[numpy.float64[m, 1]]¶
-
set_weight(self: exotica_core_task_maps_py.InteractionMesh, arg0: int, arg1: int, arg2: float) → None¶
-
property
-
class
exotica_core_task_maps_py.JointAccelerationBackwardDifference¶ Bases:
pyexotica._pyexotica.TaskMap-
set_previous_joint_state(self: exotica_core_task_maps_py.JointAccelerationBackwardDifference, arg0: numpy.ndarray[numpy.float64[m, 1]]) → None¶
-
-
class
exotica_core_task_maps_py.JointJerkBackwardDifference¶ Bases:
pyexotica._pyexotica.TaskMap-
set_previous_joint_state(self: exotica_core_task_maps_py.JointJerkBackwardDifference, arg0: numpy.ndarray[numpy.float64[m, 1]]) → None¶
-
-
class
exotica_core_task_maps_py.JointLimit¶ Bases:
pyexotica._pyexotica.TaskMap
-
class
exotica_core_task_maps_py.JointPose¶ Bases:
pyexotica._pyexotica.TaskMap-
property
joint_map¶
-
property
joint_ref¶
-
property
-
class
exotica_core_task_maps_py.JointTorqueMinimizationProxy¶ Bases:
pyexotica._pyexotica.TaskMap-
property
h¶
-
property
-
class
exotica_core_task_maps_py.JointVelocityBackwardDifference¶ Bases:
pyexotica._pyexotica.TaskMap-
set_previous_joint_state(self: exotica_core_task_maps_py.JointVelocityBackwardDifference, arg0: numpy.ndarray[numpy.float64[m, 1]]) → None¶
-
-
class
exotica_core_task_maps_py.JointVelocityLimitConstraint¶ Bases:
pyexotica._pyexotica.TaskMap-
set_previous_joint_state(self: exotica_core_task_maps_py.JointVelocityLimitConstraint, arg0: numpy.ndarray[numpy.float64[m, 1]]) → None¶
-
-
class
exotica_core_task_maps_py.PointToLine¶ Bases:
pyexotica._pyexotica.TaskMap-
property
end_point¶
-
property
-
class
exotica_core_task_maps_py.SphereCollision¶ Bases:
pyexotica._pyexotica.TaskMap
Exotica ILQR Solver
-
class
exotica_ilqr_solver_py.ILQRSolver¶ Bases:
pyexotica._pyexotica.FeedbackMotionSolver
Exotica DDP Solver
-
class
exotica_ddp_solver_py.AbstractDDPSolver¶ Bases:
pyexotica._pyexotica.FeedbackMotionSolver-
property
K¶
-
property
Qu¶
-
property
Quu¶
-
property
Quu_inv¶
-
property
Qux¶
-
property
Qx¶
-
property
Qxx¶
-
property
U_ref¶
-
property
U_try¶
-
property
Vx¶
-
property
Vxx¶
-
property
X_ref¶
-
property
X_try¶
-
property
control_cost_evolution¶
-
property
fu¶
-
property
fx¶
-
property
k¶
-
property
regularization_evolution¶
-
property
steplength_evolution¶
-
property
-
class
exotica_ddp_solver_py.AnalyticDDPSolver¶
-
class
exotica_ddp_solver_py.ControlLimitedDDPSolver¶
-
class
exotica_ddp_solver_py.ControlLimitedFeasibilityDrivenDDPSolver¶
-
class
exotica_ddp_solver_py.FeasibilityDrivenDDPSolver¶ Bases:
exotica_ddp_solver_py.AbstractDDPSolver-
property
fs¶
-
property
us¶
-
property
xs¶
-
property
Exotica ILQG Solver
-
class
exotica_ilqg_solver_py.ILQGSolver¶ Bases:
pyexotica._pyexotica.FeedbackMotionSolver