RcsPySim
A robot control and simulation library
AMJointControlAcceleration.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  Copyright (c) 2020, Fabio Muratore, Honda Research Institute Europe GmbH, and
3  Technical University of Darmstadt.
4  All rights reserved.
5 
6  Redistribution and use in source and binary forms, with or without
7  modification, are permitted provided that the following conditions are met:
8  1. Redistributions of source code must retain the above copyright
9  notice, this list of conditions and the following disclaimer.
10  2. 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  3. Neither the name of Fabio Muratore, Honda Research Institute Europe GmbH,
14  or Technical University of Darmstadt, nor the names of its contributors may
15  be used to endorse or promote products derived from this software without
16  specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
19  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21  DISCLAIMED. IN NO EVENT SHALL FABIO MURATORE, HONDA RESEARCH INSTITUTE EUROPE GMBH,
22  OR TECHNICAL UNIVERSITY OF DARMSTADT BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
24  PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
25  OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
26  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  POSSIBILITY OF SUCH DAMAGE.
29 *******************************************************************************/
30 
32 
33 #include <Rcs_typedef.h>
34 #include <Rcs_dynamics.h>
35 #include <Rcs_macros.h>
36 #include <Rcs_VecNd.h>
37 
38 #include <limits>
39 
40 
41 namespace Rcs
42 {
43 
44 // TODO @Felix: this does not work ATM, but I will leave it in case we want to change that later.
46 {
47  // Make sure nJ is correct
48  RcsGraph_setState(graph, NULL, NULL);
49  // Iterate unconstrained joints
50 // RCSGRAPH_TRAVERSE_JOINTS(graph)
51 // {
52 // if (JNT->jacobiIndex != -1)
53 // {
54 // // Make sure that the joints actually use torque control inside the simulation
55 // JNT->ctrlType = RCSJOINT_CTRL_TORQUE;
56 // }
57 // }
58 
59  // create temporary matrices
60  M = MatNd_create(graph->nJ, graph->nJ);
61  h = MatNd_create(graph->nJ, 1);
62  F_gravity = MatNd_create(graph->nJ, 1);
63 }
64 
66 {
67  MatNd_destroy(M);
68  MatNd_destroy(h);
69  MatNd_destroy(F_gravity);
70 }
71 
72 // TODO discuss this fcn with Michael
74  MatNd* q_des, MatNd* q_dot_des, MatNd* T_des, const MatNd* action,
75  double dt)
76 {
77  // Compute inverse dynamics
78  RcsGraph_computeKineticTerms(graph, M, h, F_gravity);
79 
80  // Use them to compute the torque. This is done in IK state vector.
81  MatNd_reshape(T_des, graph->nJ, 1);
82 
83  MatNd_mul(T_des, M, action);
84 
85  // Print if debug level is exceeded
86  REXEC(8) {
87  MatNd_printComment("M", M);
88  MatNd_printComment("M*q_dotdot_des", T_des);
89  MatNd_printComment("coriolis", h);
90  MatNd_printComment("gravity compensation", F_gravity);
91  }
92 
93  MatNd_addSelf(T_des, h);
94  MatNd_subSelf(T_des, F_gravity);
95  // Expand T_des to full state vector
96  RcsGraph_stateVectorFromIKSelf(graph, T_des);
97 }
98 
99 void AMJointControlAcceleration::getMinMax(double* min, double* max) const
100 {
101  VecNd_setElementsTo(min, -std::numeric_limits<double>::infinity(), getDim()); // rad/s^2
102  VecNd_setElementsTo(max, std::numeric_limits<double>::infinity(), getDim()); // rad/s^2
103 }
104 
106 {
107  // stable action = no acceleration
108  MatNd_setZero(action);
109 }
110 
112 {
113  return new AMJointControlAcceleration(newGraph);
114 }
115 
116 } /* namespace Rcs */
virtual void computeCommand(MatNd *q_des, MatNd *q_dot_des, MatNd *T_des, const MatNd *action, double dt)
virtual void getMinMax(double *min, double *max) const
virtual void getStableAction(MatNd *action) const
virtual unsigned int getDim() const
ActionModel * clone() const
Definition: ActionModel.h:72
RcsGraph * graph
Definition: ActionModel.h:194