forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
rbtree_py.cc
203 lines (191 loc) · 8.99 KB
/
rbtree_py.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
#include <iostream>
#include <pybind11/eigen.h>
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include "drake/bindings/pydrake/autodiff_types_py.h"
#include "drake/multibody/parsers/package_map.h"
#include "drake/multibody/parsers/urdf_parser.h"
#include "drake/multibody/rigid_body_tree.h"
namespace py = pybind11;
PYBIND11_MODULE(_rbtree_py, m) {
m.doc() = "Bindings for the RigidBodyTree class";
using drake::AutoDiffXd;
using drake::multibody::joints::FloatingBaseType;
using drake::parsers::PackageMap;
py::module::import("pydrake.parsers");
py::enum_<FloatingBaseType>(m, "FloatingBaseType")
.value("kFixed", FloatingBaseType::kFixed)
.value("kRollPitchYaw", FloatingBaseType::kRollPitchYaw)
.value("kQuaternion", FloatingBaseType::kQuaternion);
py::class_<RigidBodyTree<double>>(m, "RigidBodyTree")
.def(py::init<>())
.def("__init__",
[](RigidBodyTree<double> &instance,
const std::string& urdf_filename,
const PackageMap& pmap,
FloatingBaseType floating_base_type
) {
new (&instance) RigidBodyTree<double>();
drake::parsers::urdf::
AddModelInstanceFromUrdfFileSearchingInRosPackages(
urdf_filename,
pmap,
floating_base_type,
nullptr,
&instance);
},
py::arg("urdf_filename"),
py::arg("package_map"),
py::arg("floating_base_type") = FloatingBaseType::kRollPitchYaw)
.def("__init__",
[](RigidBodyTree<double> &instance,
const std::string& urdf_filename,
FloatingBaseType floating_base_type
) {
new (&instance) RigidBodyTree<double>();
drake::parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
urdf_filename, floating_base_type, &instance);
},
py::arg("urdf_filename"),
py::arg("floating_base_type") = FloatingBaseType::kRollPitchYaw)
.def("__init__",
[](RigidBodyTree<double> &instance,
const std::string& urdf_filename,
const std::string& joint_type) {
// FIXED = 0, ROLLPITCHYAW = 1, QUATERNION = 2
FloatingBaseType floating_base_type;
std::cerr << "WARNING: passing joint_type as a string is "
<< "deprecated. Please pass a FloatingBaseType value such as "
<< "pydrake.rbtree.FloatingBaseType.kRollPitchYaw" << std::endl;
if (joint_type == "FIXED") {
floating_base_type = FloatingBaseType::kFixed;
} else if (joint_type == "ROLLPITCHYAW") {
floating_base_type = FloatingBaseType::kRollPitchYaw;
} else if (joint_type == "QUATERNION") {
floating_base_type = FloatingBaseType::kQuaternion;
} else {
throw(std::invalid_argument("Joint type not supported"));
}
new (&instance) RigidBodyTree<double>();
drake::parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
urdf_filename, floating_base_type, &instance);
},
py::arg("urdf_filename"), py::arg("joint_type") = "ROLLPITCHYAW"
)
.def("getRandomConfiguration", [](const RigidBodyTree<double>& tree) {
std::default_random_engine generator(std::random_device {}());
return tree.getRandomConfiguration(generator);
})
.def("getZeroConfiguration", &RigidBodyTree<double>::getZeroConfiguration)
.def("doKinematics", [](const RigidBodyTree<double>& tree,
const Eigen::VectorXd& q) {
return tree.doKinematics(q);
})
.def("doKinematics", [](const RigidBodyTree<double>& tree,
const Eigen::VectorXd& q,
const Eigen::VectorXd& v) {
return tree.doKinematics(q, v);
})
.def("doKinematics", [](const RigidBodyTree<double>& tree,
const VectorXAutoDiffXd& q) {
return tree.doKinematics(q);
})
.def("doKinematics", [](const RigidBodyTree<double>& tree,
const VectorXAutoDiffXd& q,
const VectorXAutoDiffXd& v) {
return tree.doKinematics(q, v);
})
.def("centerOfMass", &RigidBodyTree<double>::centerOfMass<double>,
py::arg("cache"),
py::arg("model_instance_id_set") =
RigidBodyTreeConstants::default_model_instance_id_set)
.def("centerOfMassJacobian",
&RigidBodyTree<double>::centerOfMassJacobian<double>,
py::arg("cache"),
py::arg("model_instance_id_set") =
RigidBodyTreeConstants::default_model_instance_id_set,
py::arg("in_terms_of_qdot") = false)
.def("get_num_bodies", &RigidBodyTree<double>::get_num_bodies)
.def("get_num_frames", &RigidBodyTree<double>::get_num_frames)
.def("getBodyOrFrameName",
&RigidBodyTree<double>::getBodyOrFrameName,
py::arg("body_or_frame_id"))
.def("number_of_positions", &RigidBodyTree<double>::get_num_positions)
.def("get_num_positions", &RigidBodyTree<double>::get_num_positions)
.def("number_of_velocities", &RigidBodyTree<double>::get_num_velocities)
.def("get_num_velocities", &RigidBodyTree<double>::get_num_velocities)
.def("get_body", &RigidBodyTree<double>::get_body,
py::return_value_policy::reference)
.def("get_position_name", &RigidBodyTree<double>::get_position_name)
.def("transformPoints", [](const RigidBodyTree<double>& tree,
const KinematicsCache<double>& cache,
const Eigen::Matrix<double, 3,
Eigen::Dynamic>& points,
int from_body_or_frame_ind,
int to_body_or_frame_ind) {
return tree.transformPoints(cache, points,
from_body_or_frame_ind, to_body_or_frame_ind);
})
.def("transformPoints", [](const RigidBodyTree<double>& tree,
const KinematicsCache<AutoDiffXd>& cache,
const Eigen::Matrix<double, 3,
Eigen::Dynamic>& points,
int from_body_or_frame_ind,
int to_body_or_frame_ind) {
return tree.transformPoints(cache, points,
from_body_or_frame_ind, to_body_or_frame_ind);
})
.def("relativeTransform", [](const RigidBodyTree<double>& tree,
const KinematicsCache<double>& cache,
int base_or_frame_ind,
int body_or_frame_ind) {
return tree.relativeTransform(cache, base_or_frame_ind,
body_or_frame_ind).matrix();
})
.def("relativeTransform", [](const RigidBodyTree<double>& tree,
const KinematicsCache<AutoDiffXd>& cache,
int base_or_frame_ind,
int body_or_frame_ind) {
return tree.relativeTransform(cache, base_or_frame_ind,
body_or_frame_ind).matrix();
})
.def("addFrame", &RigidBodyTree<double>::addFrame)
.def("FindBody", [](const RigidBodyTree<double>& self,
const std::string& body_name,
const std::string& model_name = "",
int model_id = -1) {
return self.FindBody(body_name, model_name, model_id);
}, py::arg("body_name"),
py::arg("model_name") = "",
py::arg("model_id") = -1,
py::return_value_policy::reference)
.def("world",
static_cast<RigidBody<double>& (RigidBodyTree<double>::*)()>(
&RigidBodyTree<double>::world),
py::return_value_policy::reference)
.def("findFrame", &RigidBodyTree<double>::findFrame,
py::arg("frame_name"), py::arg("model_id") = -1)
.def("getTerrainContactPoints",
[](const RigidBodyTree<double>& self,
const RigidBody<double>& body,
const std::string& group_name = "") {
auto pts = Eigen::Matrix3Xd(3, 0);
self.getTerrainContactPoints(body, &pts, group_name);
return pts;
}, py::arg("body"), py::arg("group_name")="");
py::class_<KinematicsCache<double> >(m, "KinematicsCacheDouble");
py::class_<KinematicsCache<AutoDiffXd> >(m, "KinematicsCacheAutoDiffXd");
py::class_<RigidBody<double> >(m, "RigidBody")
.def("get_name", &RigidBody<double>::get_name)
.def("get_body_index", &RigidBody<double>::get_body_index);
py::class_<RigidBodyFrame<double>,
std::shared_ptr<RigidBodyFrame<double> > >(m, "RigidBodyFrame")
.def(py::init<const std::string&,
RigidBody<double>*,
const Eigen::VectorXd&,
const Eigen::VectorXd& >())
.def("get_frame_index", &RigidBodyFrame<double>::get_frame_index);
m.def("AddModelInstanceFromUrdfStringSearchingInRosPackages",
&drake::parsers::urdf::\
AddModelInstanceFromUrdfStringSearchingInRosPackages);
}