| // Copyright 2022 DeepMind Technologies Limited | |
| // | |
| // Licensed under the Apache License, Version 2.0 (the "License"); | |
| // you may not use this file except in compliance with the License. | |
| // You may obtain a copy of the License at | |
| // | |
| // http://www.apache.org/licenses/LICENSE-2.0 | |
| // | |
| // Unless required by applicable law or agreed to in writing, software | |
| // distributed under the License is distributed on an "AS IS" BASIS, | |
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | |
| // See the License for the specific language governing permissions and | |
| // limitations under the License. | |
| extern "C" { | |
| // derivatives of mju_subQuat w.r.t inputs | |
| MJAPI void mjd_subQuat(const mjtNum qa[4], const mjtNum qb[4], mjtNum Da[9], mjtNum Db[9]); | |
| // derivatives of mju_quatIntegrate w.r.t inputs | |
| MJAPI void mjd_quatIntegrate(const mjtNum vel[3], mjtNum scale, | |
| mjtNum Dquat[9], mjtNum Dvel[9], mjtNum Dscale[3]); | |
| // analytical derivative of smooth forces w.r.t velocities: | |
| // d->qDeriv = d (qfrc_actuator + qfrc_passive - [qfrc_bias]) / d qvel | |
| MJAPI void mjd_smooth_vel(const mjModel* m, mjData* d, int flg_bias); | |
| // add (d qfrc_actuator / d qvel) to qDeriv | |
| MJAPI void mjd_actuator_vel(const mjModel* m, mjData* d); | |
| // add (d qfrc_passive / d qvel) to qDeriv | |
| MJAPI void mjd_passive_vel(const mjModel* m, mjData* d); | |
| // subtract (d qfrc_bias / d qvel) from qDeriv (dense version) | |
| MJAPI void mjd_rne_vel_dense(const mjModel* m, mjData* d); | |
| } | |