14 #include <Eigen/Dense> 15 #include <unsupported/Eigen/AutoDiff> 21 template <std::
size_t Size>
23 std::array<int, Size> ret;
24 for (
unsigned int i = 0; i < Size; i++) {
33 template <
typename DerivedA,
typename DerivedB,
typename DerivedDA>
35 typedef typename Eigen::Matrix<
36 typename DerivedA::Scalar,
37 (DerivedA::RowsAtCompileTime == Eigen::Dynamic ||
38 DerivedB::ColsAtCompileTime == Eigen::Dynamic
40 : DerivedA::RowsAtCompileTime * DerivedB::ColsAtCompileTime),
41 DerivedDA::ColsAtCompileTime>
type;
47 template <
typename DerivedDA,
typename DerivedB>
49 typedef typename Eigen::Matrix<
50 typename DerivedDA::Scalar,
51 (DerivedDA::RowsAtCompileTime == Eigen::Dynamic ||
52 DerivedB::SizeAtCompileTime == Eigen::Dynamic
54 : DerivedDA::RowsAtCompileTime / DerivedB::RowsAtCompileTime *
55 DerivedB::ColsAtCompileTime),
56 DerivedDA::ColsAtCompileTime>
type;
63 template <
int QSubvectorSize,
typename Derived, std::size_t NRows,
66 typedef typename Eigen::Matrix<
typename Derived::Scalar, (NRows * NCols),
67 ((QSubvectorSize == Eigen::Dynamic)
68 ? Derived::ColsAtCompileTime
75 template <
int QSubvectorSize,
typename Derived>
77 typedef typename Eigen::Block<
const Derived, 1,
78 ((QSubvectorSize == Eigen::Dynamic)
79 ? Derived::ColsAtCompileTime
88 template <
typename Derived>
90 const Eigen::MatrixBase<Derived>& dX,
typename Derived::Index rows_X) {
91 typename Derived::PlainObject dX_transpose(dX.rows(), dX.cols());
92 typename Derived::Index numel = dX.rows();
93 typename Derived::Index index = 0;
94 for (
int i = 0; i < numel; i++) {
95 dX_transpose.row(i) = dX.row(index);
98 index = (index % numel) + 1;
104 template <
typename DerivedA,
typename DerivedB,
typename DerivedDA,
107 const Eigen::MatrixBase<DerivedA>&
A,
const Eigen::MatrixBase<DerivedB>&
B,
108 const Eigen::MatrixBase<DerivedDA>& dA,
109 const Eigen::MatrixBase<DerivedDB>& dB) {
113 A.rows() * B.cols(), dA.cols());
115 for (
int col = 0; col < B.cols(); col++) {
116 auto block = ret.template block<DerivedA::RowsAtCompileTime,
117 DerivedDA::ColsAtCompileTime>(
118 col * A.rows(), 0, A.rows(), dA.cols());
121 block.noalias() = A *
122 dB.template block<DerivedA::ColsAtCompileTime,
123 DerivedDA::ColsAtCompileTime>(
124 col * A.cols(), 0, A.cols(), dA.cols());
126 for (
int row = 0; row < B.rows(); row++) {
128 block.noalias() +=
B(row, col) *
129 dA.template block<DerivedA::RowsAtCompileTime,
130 DerivedDA::ColsAtCompileTime>(
131 row * A.rows(), 0, A.rows(), dA.cols());
142 template <
typename DerivedDA,
typename DerivedB>
144 const Eigen::MatrixBase<DerivedDA>& dA,
145 const Eigen::MatrixBase<DerivedB>&
B) {
146 DRAKE_ASSERT(B.rows() == 0 ? dA.rows() == 0 : dA.rows() % B.rows() == 0);
147 typename DerivedDA::Index A_rows = B.rows() == 0 ? 0 : dA.rows() / B.rows();
148 const int A_rows_at_compile_time =
149 (DerivedDA::RowsAtCompileTime == Eigen::Dynamic ||
150 DerivedB::RowsAtCompileTime == Eigen::Dynamic)
152 : static_cast<int>(DerivedDA::RowsAtCompileTime /
153 DerivedB::RowsAtCompileTime);
158 for (
int col = 0; col < B.cols(); col++) {
159 auto block = ret.template block<A_rows_at_compile_time,
160 DerivedDA::ColsAtCompileTime>(
161 col * A_rows, 0, A_rows, dA.cols());
162 for (
int row = 0; row < B.rows(); row++) {
164 block.noalias() +=
B(row, col) *
165 dA.template block<A_rows_at_compile_time,
166 DerivedDA::ColsAtCompileTime>(
167 row * A_rows, 0, A_rows, dA.cols());
175 template <
typename Derived>
176 Eigen::Matrix<typename Derived::Scalar, Eigen::Dynamic, Eigen::Dynamic>
178 const std::vector<int>& rows,
const std::vector<int>& cols,
179 typename Derived::Index M_rows,
int q_start = 0,
180 typename Derived::Index q_subvector_size = -1) {
181 if (q_subvector_size < 0) {
182 q_subvector_size = dM.cols() - q_start;
184 Eigen::MatrixXd dM_submatrix(rows.size() * cols.size(), q_subvector_size);
186 for (std::vector<int>::const_iterator col = cols.begin(); col != cols.end();
188 for (std::vector<int>::const_iterator row = rows.begin(); row != rows.end();
190 dM_submatrix.row(index) =
191 dM.block(*row + *col * M_rows, q_start, 1, q_subvector_size);
198 template <
int QSubvectorSize,
typename Derived, std::size_t NRows,
202 const Eigen::MatrixBase<Derived>& dM,
const std::array<int, NRows>& rows,
203 const std::array<int, NCols>& cols,
typename Derived::Index M_rows,
205 typename Derived::Index q_subvector_size = QSubvectorSize) {
206 if (q_subvector_size == Eigen::Dynamic) {
207 q_subvector_size = dM.cols() - q_start;
209 Eigen::Matrix<
typename Derived::Scalar, NRows * NCols,
210 Derived::ColsAtCompileTime> dM_submatrix(NRows * NCols,
213 for (
typename std::array<int, NCols>::const_iterator col = cols.begin();
214 col != cols.end(); ++col) {
215 for (
typename std::array<int, NRows>::const_iterator row = rows.begin();
216 row != rows.end(); ++row) {
217 dM_submatrix.row(index++) = dM.template block<1, QSubvectorSize>(
218 (*row) + (*col) * M_rows, q_start, 1, q_subvector_size);
224 template <
int QSubvectorSize,
typename Derived>
227 const Eigen::MatrixBase<Derived>& dM,
int row,
int col,
228 typename Derived::Index M_rows,
typename Derived::Index q_start = 0,
229 typename Derived::Index q_subvector_size = QSubvectorSize) {
230 if (q_subvector_size == Eigen::Dynamic) {
231 q_subvector_size = dM.cols() - q_start;
233 return dM.template block<1, QSubvectorSize>(row + col * M_rows, q_start, 1,
237 template <
typename DerivedA,
typename DerivedB>
239 const Eigen::MatrixBase<DerivedB>& dM_submatrix,
240 const std::vector<int>& rows,
241 const std::vector<int>& cols,
242 typename DerivedA::Index M_rows,
243 typename DerivedA::Index q_start = 0,
244 typename DerivedA::Index q_subvector_size = -1) {
245 if (q_subvector_size < 0) {
246 q_subvector_size = dM.cols() - q_start;
249 for (
typename std::vector<int>::const_iterator col = cols.begin();
250 col != cols.end(); ++col) {
251 for (
typename std::vector<int>::const_iterator row = rows.begin();
252 row != rows.end(); ++row) {
253 dM.block((*row) + (*col) * M_rows, q_start, 1, q_subvector_size) =
254 dM_submatrix.row(index++);
259 template <
int QSubvectorSize,
typename DerivedA,
typename DerivedB,
260 std::size_t NRows, std::size_t NCols>
262 Eigen::MatrixBase<DerivedA>& dM,
263 const Eigen::MatrixBase<DerivedB>& dM_submatrix,
264 const std::array<int, NRows>& rows,
const std::array<int, NCols>& cols,
265 typename DerivedA::Index M_rows,
typename DerivedA::Index q_start = 0,
266 typename DerivedA::Index q_subvector_size = QSubvectorSize) {
267 if (q_subvector_size == Eigen::Dynamic) {
268 q_subvector_size = dM.cols() - q_start;
271 for (
typename std::array<int, NCols>::const_iterator col = cols.begin();
272 col != cols.end(); ++col) {
273 for (
typename std::array<int, NRows>::const_iterator row = rows.begin();
274 row != rows.end(); ++row) {
275 dM.template block<1, QSubvectorSize>((*row) + (*col) * M_rows, q_start, 1,
277 dM_submatrix.row(index++);
282 template <
int QSubvectorSize,
typename DerivedDM,
typename DerivedDMSub>
284 Eigen::MatrixBase<DerivedDM>& dM,
285 const Eigen::MatrixBase<DerivedDMSub>& dM_submatrix,
int row,
int col,
286 typename DerivedDM::Index M_rows,
typename DerivedDM::Index q_start = 0,
287 typename DerivedDM::Index q_subvector_size = QSubvectorSize) {
288 if (q_subvector_size == Eigen::Dynamic) {
289 q_subvector_size = dM.cols() - q_start;
291 dM.template block<1, QSubvectorSize>(row + col * M_rows, q_start, 1,
292 q_subvector_size) = dM_submatrix;
295 template <
typename DerivedGradient,
typename DerivedAutoDiff>
297 const Eigen::MatrixBase<DerivedGradient>& gradient,
298 Eigen::MatrixBase<DerivedAutoDiff>& auto_diff_matrix) {
299 typedef typename Eigen::MatrixBase<DerivedGradient>::Index Index;
300 auto nx = gradient.cols();
301 for (Index row = 0; row < auto_diff_matrix.rows(); row++) {
302 for (Index col = 0; col < auto_diff_matrix.cols(); col++) {
303 auto_diff_matrix(row, col).derivatives().resize(
nx, 1);
304 auto_diff_matrix(row, col).derivatives() =
305 gradient.row(row + col * auto_diff_matrix.rows()).transpose();
312 template <
typename Derived,
typename Scalar>
314 static void run(Eigen::MatrixBase<Derived>& mat,
const Scalar& scalar){}
317 template <
typename Derived,
typename DerivType>
319 Eigen::AutoDiffScalar<DerivType> > {
320 using Scalar = Eigen::AutoDiffScalar<DerivType>;
321 static void run(Eigen::MatrixBase<Derived>& mat,
const Scalar& scalar) {
322 for (
int i = 0; i < mat.size(); i++) {
323 auto& derivs = mat(i).derivatives();
324 if (derivs.size() == 0) {
325 derivs.resize(scalar.derivatives().size());
345 template <
typename Derived>
347 const typename Derived::Scalar& scalar) {
349 Derived,
typename Derived::Scalar>::run(mat, scalar);
static void run(Eigen::MatrixBase< Derived > &mat, const Scalar &scalar)
Definition: drakeGradientUtil.h:321
static void run(Eigen::MatrixBase< Derived > &mat, const Scalar &scalar)
Definition: drakeGradientUtil.h:314
MatGradMult< DerivedDA, DerivedB >::type matGradMult(const Eigen::MatrixBase< DerivedDA > &dA, const Eigen::MatrixBase< DerivedB > &B)
Definition: drakeGradientUtil.h:143
Eigen::Matrix< typename DerivedA::Scalar,(DerivedA::RowsAtCompileTime==Eigen::Dynamic||DerivedB::ColsAtCompileTime==Eigen::Dynamic?Eigen::Dynamic:DerivedA::RowsAtCompileTime *DerivedB::ColsAtCompileTime), DerivedDA::ColsAtCompileTime > type
Definition: drakeGradientUtil.h:41
NOTE: The contents of this class are for the most part direct ports of drake/systems/plants//inverseK...
Definition: Function.h:14
Eigen::AutoDiffScalar< DerivType > Scalar
Definition: drakeGradientUtil.h:320
Eigen::Matrix< typename Derived::Scalar,(NRows *NCols),((QSubvectorSize==Eigen::Dynamic)?Derived::ColsAtCompileTime:QSubvectorSize)> type
Definition: drakeGradientUtil.h:69
Definition: drakeGradientUtil.h:313
Eigen::Matrix< typename DerivedDA::Scalar,(DerivedDA::RowsAtCompileTime==Eigen::Dynamic||DerivedB::SizeAtCompileTime==Eigen::Dynamic?Eigen::Dynamic:DerivedDA::RowsAtCompileTime/DerivedB::RowsAtCompileTime *DerivedB::ColsAtCompileTime), DerivedDA::ColsAtCompileTime > type
Definition: drakeGradientUtil.h:56
void setSubMatrixGradient(Eigen::MatrixBase< DerivedA > &dM, const Eigen::MatrixBase< DerivedB > &dM_submatrix, const std::vector< int > &rows, const std::vector< int > &cols, typename DerivedA::Index M_rows, typename DerivedA::Index q_start=0, typename DerivedA::Index q_subvector_size=-1)
Definition: drakeGradientUtil.h:238
Definition: drakeGradientUtil.h:48
#define DRAKE_ASSERT(condition)
DRAKE_ASSERT(condition) is similar to the built-in assert(condition) from the C++ system header <cas...
Definition: drake_assert.h:35
void resizeDerivativesToMatchScalar(Eigen::MatrixBase< Derived > &mat, const typename Derived::Scalar &scalar)
Resize derivatives vector of each element of a matrix to to match the size of the derivatives vector ...
Definition: drakeGradientUtil.h:346
Provides Drake's assertion implementation.
MatGradMultMat< DerivedA, DerivedB, DerivedDA >::type matGradMultMat(const Eigen::MatrixBase< DerivedA > &A, const Eigen::MatrixBase< DerivedB > &B, const Eigen::MatrixBase< DerivedDA > &dA, const Eigen::MatrixBase< DerivedDB > &dB)
Definition: drakeGradientUtil.h:106
static snopt::integer nx
Definition: inverseKinSnoptBackend.cpp:54
Eigen::Block< const Derived, 1,((QSubvectorSize==Eigen::Dynamic)?Derived::ColsAtCompileTime:QSubvectorSize)> type
Definition: drakeGradientUtil.h:80
Definition: drakeGradientUtil.h:34
void gradientMatrixToAutoDiff(const Eigen::MatrixBase< DerivedGradient > &gradient, Eigen::MatrixBase< DerivedAutoDiff > &auto_diff_matrix)
Definition: drakeGradientUtil.h:296
Definition: drakeGradientUtil.h:65
std::array< int, Size > intRange(int start)
Definition: drakeGradientUtil.h:22
Eigen::Matrix< typename Derived::Scalar, Eigen::Dynamic, Eigen::Dynamic > getSubMatrixGradient(const Eigen::MatrixBase< Derived > &dM, const std::vector< int > &rows, const std::vector< int > &cols, typename Derived::Index M_rows, int q_start=0, typename Derived::Index q_subvector_size=-1)
Definition: drakeGradientUtil.h:177
Derived::PlainObject transposeGrad(const Eigen::MatrixBase< Derived > &dX, typename Derived::Index rows_X)
Definition: drakeGradientUtil.h:89
Definition: drakeGradientUtil.h:76