Skip to content

Commit 350f0c4

Browse files
erez-tomcopybara-github
authored andcommitted
Rename task: hand->shadow_reorient.
PiperOrigin-RevId: 607647773 Change-Id: Iee71181fdc79c91e55aea7fd74b5724b84a45963
1 parent f2b4b91 commit 350f0c4

File tree

6 files changed

+21
-22
lines changed

6 files changed

+21
-22
lines changed

mjpc/tasks/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ add_custom_target(
6464
## Menagerie models
6565
COMMAND ${CMAKE_COMMAND} -E copy
6666
${menagerie_SOURCE_DIR}/shadow_hand/right_hand.xml
67-
${CMAKE_CURRENT_BINARY_DIR}/hand/right_hand.xml
67+
${CMAKE_CURRENT_BINARY_DIR}/shadow_reorient/right_hand.xml
6868
COMMAND ${CMAKE_COMMAND} -E copy
6969
${menagerie_SOURCE_DIR}/wonik_allegro/right_hand.xml
7070
${CMAKE_CURRENT_BINARY_DIR}/allegro/right_hand.xml
@@ -76,7 +76,7 @@ add_custom_target(
7676
<${CMAKE_CURRENT_SOURCE_DIR}/allegro/right_hand.xml.patch
7777
COMMAND ${CMAKE_COMMAND} -E copy_directory
7878
${menagerie_SOURCE_DIR}/shadow_hand/assets
79-
${CMAKE_CURRENT_BINARY_DIR}/hand/assets
79+
${CMAKE_CURRENT_BINARY_DIR}/shadow_reorient/assets
8080
COMMAND ${CMAKE_COMMAND} -E copy
8181
${menagerie_SOURCE_DIR}/franka_emika_panda/panda.xml
8282
${CMAKE_CURRENT_BINARY_DIR}/panda/panda.xml

mjpc/tasks/hand/hand.cc renamed to mjpc/tasks/shadow_reorient/hand.cc

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -12,21 +12,18 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "mjpc/tasks/hand/hand.h"
15+
#include "mjpc/tasks/shadow_reorient/hand.h"
1616

1717
#include <string>
1818

19-
#include <absl/log/check.h>
20-
#include <absl/log/log.h>
2119
#include <mujoco/mujoco.h>
22-
#include "mjpc/task.h"
2320
#include "mjpc/utilities.h"
2421

2522
namespace mjpc {
26-
std::string Hand::XmlPath() const {
27-
return GetModelPath("hand/task.xml");
23+
std::string ShadowReorient::XmlPath() const {
24+
return GetModelPath("shadow_reorient/task.xml");
2825
}
29-
std::string Hand::Name() const { return "Hand"; }
26+
std::string ShadowReorient::Name() const { return "Shadow"; }
3027

3128
// ---------- Residuals for in-hand manipulation task ---------
3229
// Number of residuals: 6
@@ -37,8 +34,9 @@ std::string Hand::Name() const { return "Hand"; }
3734
// Residual (4): hand configuration - nominal hand configuration
3835
// Residual (5): hand joint velocity
3936
// ------------------------------------------------------------
40-
void Hand::ResidualFn::Residual(const mjModel* model, const mjData* data,
41-
double* residual) const {
37+
void ShadowReorient::ResidualFn::Residual(const mjModel* model,
38+
const mjData* data,
39+
double* residual) const {
4240
int counter = 0;
4341
// ---------- Residual (0) ----------
4442
// goal position
@@ -89,7 +87,7 @@ void Hand::ResidualFn::Residual(const mjModel* model, const mjData* data,
8987
// If cube is within tolerance or floor ->
9088
// reset cube into hand.
9189
// -----------------------------------------------
92-
void Hand::TransitionLocked(mjModel* model, mjData* data) {
90+
void ShadowReorient::TransitionLocked(mjModel* model, mjData* data) {
9391
// find cube and floor
9492
int cube = mj_name2id(model, mjOBJ_GEOM, "cube");
9593
int floor = mj_name2id(model, mjOBJ_GEOM, "floor");

mjpc/tasks/hand/hand.h renamed to mjpc/tasks/shadow_reorient/hand.h

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -12,21 +12,22 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef MJPC_TASKS_HAND_HAND_H_
16-
#define MJPC_TASKS_HAND_HAND_H_
15+
#ifndef MJPC_TASKS_SHADOW_REORIENT_HAND_H_
16+
#define MJPC_TASKS_SHADOW_REORIENT_HAND_H_
1717

18+
#include <memory>
1819
#include <string>
1920
#include <mujoco/mujoco.h>
2021
#include "mjpc/task.h"
2122

2223
namespace mjpc {
23-
class Hand : public Task {
24+
class ShadowReorient : public Task {
2425
public:
2526
std::string Name() const override;
2627
std::string XmlPath() const override;
2728
class ResidualFn : public BaseResidualFn {
2829
public:
29-
explicit ResidualFn(const Hand* task) : BaseResidualFn(task) {}
30+
explicit ResidualFn(const ShadowReorient* task) : BaseResidualFn(task) {}
3031

3132
// ---------- Residuals for in-hand manipulation task ---------
3233
// Number of residuals: 5
@@ -39,7 +40,7 @@ class Hand : public Task {
3940
void Residual(const mjModel* model, const mjData* data,
4041
double* residual) const override;
4142
};
42-
Hand() : residual_(this) {}
43+
ShadowReorient() : residual_(this) {}
4344

4445
// ----- Transition for in-hand manipulation task -----
4546
// If cube is within tolerance or floor ->
@@ -59,4 +60,4 @@ class Hand : public Task {
5960
};
6061
} // namespace mjpc
6162

62-
#endif // MJPC_TASKS_HAND_HAND_H_
63+
#endif // MJPC_TASKS_SHADOW_REORIENT_HAND_H_
File renamed without changes.

mjpc/tasks/tasks.cc

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -24,17 +24,17 @@
2424
#include "mjpc/tasks/cartpole/cartpole.h"
2525
#include "mjpc/tasks/cube/solve.h"
2626
#include "mjpc/tasks/fingers/fingers.h"
27-
#include "mjpc/tasks/hand/hand.h"
2827
#include "mjpc/tasks/humanoid/stand/stand.h"
2928
#include "mjpc/tasks/humanoid/tracking/tracking.h"
3029
#include "mjpc/tasks/humanoid/walk/walk.h"
3130
#include "mjpc/tasks/manipulation/manipulation.h"
32-
#include "mjpc/tasks/panda/panda.h"
3331
// DEEPMIND INTERNAL IMPORT
3432
#include "mjpc/tasks/op3/stand.h"
33+
#include "mjpc/tasks/panda/panda.h"
3534
#include "mjpc/tasks/particle/particle.h"
3635
#include "mjpc/tasks/quadrotor/quadrotor.h"
3736
#include "mjpc/tasks/quadruped/quadruped.h"
37+
#include "mjpc/tasks/shadow_reorient/hand.h"
3838
#include "mjpc/tasks/swimmer/swimmer.h"
3939
#include "mjpc/tasks/walker/walker.h"
4040

@@ -48,7 +48,6 @@ std::vector<std::shared_ptr<Task>> GetTasks() {
4848
std::make_shared<CubeSolve>(),
4949
std::make_shared<Cartpole>(),
5050
std::make_shared<Fingers>(),
51-
std::make_shared<Hand>(),
5251
std::make_shared<humanoid::Stand>(),
5352
std::make_shared<humanoid::Tracking>(),
5453
std::make_shared<humanoid::Walk>(),
@@ -58,6 +57,7 @@ std::vector<std::shared_ptr<Task>> GetTasks() {
5857
std::make_shared<Panda>(),
5958
std::make_shared<Particle>(),
6059
std::make_shared<ParticleFixed>(),
60+
std::make_shared<ShadowReorient>(),
6161
std::make_shared<Quadrotor>(),
6262
std::make_shared<QuadrupedFlat>(),
6363
std::make_shared<QuadrupedHill>(),

python/mujoco_mpc/demos/predictive_sampling/cube_orientation.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525

2626
model_path = (
2727
pathlib.Path(os.path.abspath("")).parent.parent.parent
28-
/ "mujoco_mpc/mjpc/tasks/hand/task.xml"
28+
/ "mujoco_mpc/mjpc/tasks/shadow/task.xml"
2929
)
3030
# create simulation model + data
3131
model = mujoco.MjModel.from_xml_path(str(model_path))

0 commit comments

Comments
 (0)