task_map_py.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #undef NDEBUG
31 #include <pybind11/eigen.h>
32 #include <pybind11/pybind11.h>
33 #include <pybind11/stl.h>
34 
54 
55 using namespace exotica;
56 namespace py = pybind11;
57 
58 PYBIND11_MODULE(exotica_core_task_maps_py, module)
59 {
60  module.doc() = "Exotica task map definitions";
61 
62  py::module::import("pyexotica");
63 
64  py::class_<ControlRegularization, std::shared_ptr<ControlRegularization>, TaskMap>(module, "ControlRegularization")
65  .def_property_readonly("joint_map", &ControlRegularization::get_joint_map)
66  .def_property_readonly("joint_ref", &ControlRegularization::get_joint_ref); // TODO: Make write-able
67 
68  py::class_<EffFrame, std::shared_ptr<EffFrame>, TaskMap>(module, "EffFrame")
69  .def_property_readonly("rotation_type", &EffFrame::get_rotation_type);
70 
71  py::class_<EffPosition, std::shared_ptr<EffPosition>, TaskMap>(module, "EffPosition");
72 
73  py::class_<EffOrientation, std::shared_ptr<EffOrientation>, TaskMap>(module, "EffOrientation")
74  .def_property_readonly("rotation_type", &EffOrientation::get_rotation_type);
75 
76  py::class_<EffAxisAlignment, std::shared_ptr<EffAxisAlignment>, TaskMap>(module, "EffAxisAlignment")
77  .def("get_axis", &EffAxisAlignment::GetAxis)
78  .def("set_axis", &EffAxisAlignment::SetAxis)
79  .def("get_direction", &EffAxisAlignment::GetDirection)
80  .def("set_direction", &EffAxisAlignment::SetDirection);
81 
82  py::class_<EffBox, std::shared_ptr<EffBox>, TaskMap>(module, "EffBox")
83  .def("get_lower_limit", &EffBox::GetLowerLimit)
84  .def("get_upper_limit", &EffBox::GetUpperLimit);
85 
86  py::class_<PointToLine, std::shared_ptr<PointToLine>, TaskMap>(module, "PointToLine")
87  .def_property("end_point", &PointToLine::GetEndPoint, &PointToLine::SetEndPoint);
88 
89  py::class_<JointVelocityLimitConstraint, std::shared_ptr<JointVelocityLimitConstraint>, TaskMap>(module, "JointVelocityLimitConstraint")
90  .def("set_previous_joint_state", &JointVelocityLimitConstraint::SetPreviousJointState);
91 
92  py::class_<JointVelocityBackwardDifference, std::shared_ptr<JointVelocityBackwardDifference>, TaskMap>(module, "JointVelocityBackwardDifference")
93  .def("set_previous_joint_state", &JointVelocityBackwardDifference::SetPreviousJointState);
94 
95  py::class_<JointAccelerationBackwardDifference, std::shared_ptr<JointAccelerationBackwardDifference>, TaskMap>(module, "JointAccelerationBackwardDifference")
96  .def("set_previous_joint_state", &JointAccelerationBackwardDifference::SetPreviousJointState);
97 
98  py::class_<JointJerkBackwardDifference, std::shared_ptr<JointJerkBackwardDifference>, TaskMap>(module, "JointJerkBackwardDifference")
99  .def("set_previous_joint_state", &JointJerkBackwardDifference::SetPreviousJointState);
100 
101  py::class_<CenterOfMass, std::shared_ptr<CenterOfMass>, TaskMap>(module, "CenterOfMass");
102 
103  py::class_<Distance, std::shared_ptr<Distance>, TaskMap>(module, "Distance");
104 
105  py::class_<JointPose, std::shared_ptr<JointPose>, TaskMap>(module, "JointPose")
106  .def_property_readonly("joint_map", &JointPose::get_joint_map)
107  .def_property("joint_ref", &JointPose::get_joint_ref, &JointPose::set_joint_ref);
108 
109  py::class_<JointTorqueMinimizationProxy, std::shared_ptr<JointTorqueMinimizationProxy>, TaskMap>(module, "JointTorqueMinimizationProxy")
111 
112  py::class_<InteractionMesh, std::shared_ptr<InteractionMesh>, TaskMap>(module, "InteractionMesh")
114  .def("set_weight", &InteractionMesh::SetWeight)
115  .def_static("compute_goal_laplace", [](const std::vector<KDL::Frame>& nodes, Eigen::MatrixXdRefConst weights) {
116  Eigen::VectorXd goal;
117  InteractionMesh::ComputeGoalLaplace(nodes, goal, weights);
118  return goal;
119  })
120  .def_static("compute_laplace", [](Eigen::VectorXdRefConst eff_phi, Eigen::MatrixXdRefConst weights) {
121  return InteractionMesh::ComputeLaplace(eff_phi, weights);
122  });
123 
124  py::class_<JointLimit, std::shared_ptr<JointLimit>, TaskMap>(module, "JointLimit");
125 
126  py::class_<SphereCollision, std::shared_ptr<SphereCollision>, TaskMap>(module, "SphereCollision");
127 
128  py::class_<CollisionDistance, std::shared_ptr<CollisionDistance>, TaskMap>(module, "CollisionDistance")
129  .def("get_collision_proxies", &CollisionDistance::get_collision_proxies);
130 }
Eigen::Matrix< double, 6, 1 > get_h() const
void SetDirection(const std::string &frame_name, const Eigen::Vector3d &dir_in)
const Eigen::VectorXd & get_joint_ref() const
void SetPreviousJointState(Eigen::VectorXdRefConst joint_state)
Logs current joint state. SetPreviousJointState must be called after solve is called in a Python/C++ ...
void SetWeight(int i, int j, double weight)
void set_h(const Eigen::Matrix< double, 6, 1 > &h_in)
const RotationType & get_rotation_type() const
Definition: eff_frame.cpp:102
Eigen::MatrixXd GetWeights()
Eigen::Vector3d GetAxis(const std::string &frame_name) const
const RotationType & get_rotation_type() const
const std::vector< int > & get_joint_map() const
Definition: joint_pose.cpp:104
Eigen::Vector3d GetDirection(const std::string &frame_name) const
void set_joint_ref(Eigen::VectorXdRefConst ref)
Definition: joint_pose.cpp:114
const Eigen::Ref< const Eigen::MatrixXd > & MatrixXdRefConst
void SetPreviousJointState(Eigen::VectorXdRefConst joint_state)
Logs previous joint state. SetPreviousJointState must be called after solve is called in a Python/C++...
void SetAxis(const std::string &frame_name, const Eigen::Vector3d &axis_in)
PYBIND11_MODULE(exotica_core_task_maps_py, module)
Definition: task_map_py.cpp:58
Eigen::Vector3d GetUpperLimit(const int eff_id) const
Definition: eff_box.cpp:80
void SetWeights(const Eigen::MatrixXd &weights)
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
void SetPreviousJointState(Eigen::VectorXdRefConst joint_state)
Logs previous joint state. SetPreviousJointState must be called after solve is called in a Python/C++...
const std::vector< int > & get_joint_map() const
const Eigen::VectorXd & get_joint_ref() const
Definition: joint_pose.cpp:109
void ComputeGoalLaplace(const Eigen::VectorXd &x, Eigen::VectorXd &goal)
static Eigen::VectorXd ComputeLaplace(Eigen::VectorXdRefConst eff_Phi, Eigen::MatrixXdRefConst weights, Eigen::MatrixXd *dist=nullptr, Eigen::VectorXd *wsum=nullptr)
Eigen::Vector3d GetEndPoint()
std::vector< CollisionProxy > get_collision_proxies()
void SetEndPoint(const Eigen::Vector3d &point)
Eigen::Vector3d GetLowerLimit(const int eff_id) const
Definition: eff_box.cpp:74
void SetPreviousJointState(Eigen::VectorXdRefConst joint_state)
Logs previous joint state. SetPreviousJointState must be called after solve is called in a Python/C++...


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09