diff --git a/mjpc/tasks/humanoid/interact/contact_keyframe.cc b/mjpc/tasks/humanoid/interact/contact_keyframe.cc index 00dc30d10..b009d2e61 100644 --- a/mjpc/tasks/humanoid/interact/contact_keyframe.cc +++ b/mjpc/tasks/humanoid/interact/contact_keyframe.cc @@ -15,6 +15,7 @@ #include "mjpc/tasks/humanoid/interact/contact_keyframe.h" namespace mjpc::humanoid { + void ContactPair::Reset() { body1 = kNotSelectedInteract; body2 = kNotSelectedInteract; diff --git a/mjpc/tasks/humanoid/interact/contact_keyframe.h b/mjpc/tasks/humanoid/interact/contact_keyframe.h index 4404d3726..1171bbc1a 100644 --- a/mjpc/tasks/humanoid/interact/contact_keyframe.h +++ b/mjpc/tasks/humanoid/interact/contact_keyframe.h @@ -15,12 +15,12 @@ #ifndef MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_ #define MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_ +#include + #include #include #include -#include "mujoco/mujoco.h" - namespace mjpc::humanoid { // ---------- Constants ----------------- // diff --git a/mjpc/tasks/humanoid/interact/interact.h b/mjpc/tasks/humanoid/interact/interact.h index ff0aa5983..df8eb2a20 100644 --- a/mjpc/tasks/humanoid/interact/interact.h +++ b/mjpc/tasks/humanoid/interact/interact.h @@ -40,10 +40,10 @@ enum TaskMode : int { // ----------- Default weights for the residual terms ----------------- // const std::vector> default_weights = { - {10., 10., 5., 5., 0., 20., 30., 0., 0., 0., 0.01, 0.1, 80.}, // sit - {10., 0., 1., 1., 80., 0., 0., 100., 0., 0., 0.01, 0.025, 0.}, // stand - {0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.01, 0.8, 80.}, // relax - {0., 0., 0., 0., 0., 0., 0., 0., 0., 50., 20., 0.025, 80.}, // stay still + {10, 10, 5, 5, 0, 20, 30, 0, 0, 0, 0.01, .1, 80.}, // to sit + {10, 0, 1, 1, 80, 0, 0, 100, 0, 0, 0.01, 0.025, 0.}, // to stand + {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, .8, 80.}, // to relax + {0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 20, .025, 80.}, // to stay still }; // ----------- Default colors for the contact pair points ------------ //