Skip to content

Commit c02baaa

Browse files
committed
Formatted files with clang and cpplint
1 parent 92cd7ae commit c02baaa

File tree

5 files changed

+159
-187
lines changed

5 files changed

+159
-187
lines changed

mjpc/CMakeLists.txt

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

15-
include(FetchContent)
16-
FetchContent_Declare(json URL https://github.com/nlohmann/json/releases/download/v3.11.3/json.tar.xz)
17-
FetchContent_MakeAvailable(json)
18-
1915
add_library(threadpool STATIC)
2016
target_sources(
2117
threadpool
@@ -167,7 +163,6 @@ target_link_libraries(
167163
mujoco::platform_ui_adapter
168164
threadpool
169165
Threads::Threads
170-
nlohmann_json::nlohmann_json
171166
)
172167
target_include_directories(libmjpc
173168
PUBLIC
@@ -189,7 +184,6 @@ target_link_libraries(
189184
mujoco::mujoco
190185
threadpool
191186
Threads::Threads
192-
nlohmann_json::nlohmann_json
193187
)
194188
target_include_directories(mjpc PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/..)
195189
target_compile_options(mjpc PUBLIC ${MJPC_COMPILE_OPTIONS})
@@ -214,7 +208,6 @@ target_link_libraries(
214208
mujoco::mujoco
215209
threadpool
216210
Threads::Threads
217-
nlohmann_json::nlohmann_json
218211
)
219212
target_include_directories(libtestspeed PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/..)
220213

mjpc/tasks/humanoid/interact/contact_keyframe.cc

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

15-
#include "contact_keyframe.h"
15+
#include "mjpc/tasks/humanoid/interact/contact_keyframe.h"
1616

1717
namespace mjpc::humanoid {
18-
void ContactPair::Reset() {
19-
body1 = kNotSelectedInteract;
20-
body2 = kNotSelectedInteract;
21-
geom1 = kNotSelectedInteract;
22-
geom2 = kNotSelectedInteract;
23-
for (int i = 0; i < 3; i++) {
24-
local_pos1[i] = 0.;
25-
local_pos2[i] = 0.;
26-
}
27-
}
28-
29-
void ContactKeyframe::Reset() {
30-
name.clear();
31-
for (auto& contact_pair : contact_pairs)
32-
contact_pair.Reset();
33-
34-
facing_target.clear();
35-
weight.clear();
36-
}
37-
38-
void to_json(json& j, const ContactPair& contact_pair) {
39-
j = json{{"body1", contact_pair.body1},
40-
{"body2", contact_pair.body2},
41-
{"geom1", contact_pair.geom1},
42-
{"geom2", contact_pair.geom2},
43-
{"local_pos1", contact_pair.local_pos1},
44-
{"local_pos2", contact_pair.local_pos2}};
45-
}
46-
47-
void from_json(const json& j, ContactPair& contact_pair) {
48-
j.at("body1").get_to(contact_pair.body1);
49-
j.at("body2").get_to(contact_pair.body2);
50-
j.at("geom1").get_to(contact_pair.geom1);
51-
j.at("geom2").get_to(contact_pair.geom2);
52-
j.at("local_pos1").get_to(contact_pair.local_pos1);
53-
j.at("local_pos2").get_to(contact_pair.local_pos2);
54-
}
18+
void ContactPair::Reset() {
19+
body1 = kNotSelectedInteract;
20+
body2 = kNotSelectedInteract;
21+
geom1 = kNotSelectedInteract;
22+
geom2 = kNotSelectedInteract;
23+
for (int i = 0; i < 3; i++) {
24+
local_pos1[i] = 0.;
25+
local_pos2[i] = 0.;
26+
}
27+
}
5528

56-
void to_json(json& j, const ContactKeyframe& keyframe) {
57-
j = json{{"name", keyframe.name},
58-
{"contacts", keyframe.contact_pairs},
59-
{"facing_target", keyframe.facing_target},
60-
{"weight", keyframe.weight}};
61-
}
29+
void ContactKeyframe::Reset() {
30+
name.clear();
31+
for (auto& contact_pair : contact_pairs) contact_pair.Reset();
6232

63-
void from_json(const json& j, ContactKeyframe& keyframe) {
64-
j.at("name").get_to(keyframe.name);
65-
j.at("contacts").get_to(keyframe.contact_pairs);
66-
j.at("facing_target").get_to(keyframe.facing_target);
67-
j.at("weight").get_to(keyframe.weight);
68-
}
33+
facing_target.clear();
34+
weight.clear();
6935
}
36+
} // namespace mjpc::humanoid

mjpc/tasks/humanoid/interact/contact_keyframe.h

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

15-
#ifndef CONTACT_KEYFRAME_H
16-
#define CONTACT_KEYFRAME_H
15+
#ifndef MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_
16+
#define MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_
1717

18-
#include <mujoco/mujoco.h>
18+
#include <map>
19+
#include <string>
1920
#include <vector>
20-
#include <nlohmann/json.hpp>
21-
using json = nlohmann::json;
21+
22+
#include "mujoco/mujoco.h"
2223

2324
namespace mjpc::humanoid {
2425

@@ -27,44 +28,37 @@ constexpr int kNotSelectedInteract = -1;
2728
constexpr int kNumberOfContactPairsInteract = 5;
2829

2930
class ContactPair {
30-
public:
31-
int body1, body2, geom1, geom2;
32-
mjtNum local_pos1[3], local_pos2[3];
31+
public:
32+
int body1, body2, geom1, geom2;
33+
mjtNum local_pos1[3], local_pos2[3];
34+
35+
ContactPair()
36+
: body1(kNotSelectedInteract),
37+
body2(kNotSelectedInteract),
38+
geom1(kNotSelectedInteract),
39+
geom2(kNotSelectedInteract),
40+
local_pos1{0.},
41+
local_pos2{0.} {}
3342

34-
ContactPair() : body1(kNotSelectedInteract),
35-
body2(kNotSelectedInteract),
36-
geom1(kNotSelectedInteract),
37-
geom2(kNotSelectedInteract),
38-
local_pos1{0.},
39-
local_pos2{0.} {}
40-
41-
void Reset();
43+
void Reset();
4244
};
4345

4446
class ContactKeyframe {
45-
public:
46-
std::string name;
47-
ContactPair contact_pairs[kNumberOfContactPairsInteract];
47+
public:
48+
std::string name;
49+
ContactPair contact_pairs[kNumberOfContactPairsInteract];
4850

49-
// the direction on the xy-plane for the torso to point towards
50-
std::vector<mjtNum> facing_target;
51-
52-
// weight of all residual terms (name -> value map)
53-
std::map<std::string, mjtNum> weight;
51+
// the direction on the xy-plane for the torso to point towards
52+
std::vector<mjtNum> facing_target;
5453

55-
ContactKeyframe() : name(""),
56-
contact_pairs{},
57-
facing_target(),
58-
weight() {}
54+
// weight of all residual terms (name -> value map)
55+
std::map<std::string, mjtNum> weight;
5956

60-
void Reset();
61-
};
57+
ContactKeyframe() : name(""), contact_pairs{}, facing_target(), weight() {}
6258

63-
void to_json(json& j, const ContactPair& contact_pair);
64-
void from_json(const json& j, ContactPair& contact_pair);
65-
void to_json(json& j, const ContactKeyframe& keyframe);
66-
void from_json(const json& j, ContactKeyframe& keyframe);
59+
void Reset();
60+
};
6761

6862
} // namespace mjpc::humanoid
6963

70-
#endif // CONTACT_KEYFRAME_H
64+
#endif // MJPC_TASKS_HUMANOID_INTERACT_CONTACT_KEYFRAME_H_

0 commit comments

Comments
 (0)