Skip to content

Commit f0d319f

Browse files
committed
fix: add shared library
1 parent 84ad889 commit f0d319f

File tree

8 files changed

+195
-39
lines changed

8 files changed

+195
-39
lines changed

BUILD.bazel

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,14 @@
1-
# This is an empty BUILD file, to ensure that the project's root directory is a
2-
# bazel package.
1+
LIBC3_COMPONENTS = [
2+
"//core:core",
3+
"//multibody:multibody",
4+
"//systems:systems",
5+
"//lcmtypes:lcmt_c3",
6+
]
7+
8+
package(default_visibility = ["//visibility:public"])
9+
10+
cc_library(
11+
name = "c3_shared_library",
12+
deps = LIBC3_COMPONENTS,
13+
include_prefix = "c3"
14+
)

bindings/pyc3/c3_multibody_py.cc

Lines changed: 17 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,9 @@
22
#include <pybind11/pybind11.h>
33

44
#include "core/lcs.h"
5-
#include "multibody/lcs_factory_options.h"
65
#include "multibody/geom_geom_collider.h"
76
#include "multibody/lcs_factory.h"
7+
#include "multibody/lcs_factory_options.h"
88
#include "multibody/multibody_utils.h"
99

1010
#include "drake/bindings/pydrake/common/sorted_pair_pybind.h"
@@ -26,6 +26,20 @@ PYBIND11_MODULE(multibody, m) {
2626
c3::multibody::ContactModel::kFrictionlessSpring)
2727
.export_values();
2828

29+
py::class_<c3::multibody::LCSContactDescription>(m, "LCSContactDescription")
30+
.def(py::init<>())
31+
.def_readwrite("witness_point_A",
32+
&c3::multibody::LCSContactDescription::witness_point_A)
33+
.def_readwrite("witness_point_B",
34+
&c3::multibody::LCSContactDescription::witness_point_B)
35+
.def_readwrite("force_basis",
36+
&c3::multibody::LCSContactDescription::force_basis)
37+
.def_readwrite("is_slack",
38+
&c3::multibody::LCSContactDescription::is_slack)
39+
.def_static("CreateSlackVariableDescription",
40+
&c3::multibody::LCSContactDescription::
41+
CreateSlackVariableDescription);
42+
2943
py::class_<c3::multibody::LCSFactory>(m, "LCSFactory")
3044
.def(py::init<const drake::multibody::MultibodyPlant<double>&,
3145
drake::systems::Context<double>&,
@@ -37,8 +51,8 @@ PYBIND11_MODULE(multibody, m) {
3751
py::arg("plant"), py::arg("context"), py::arg("plant_ad"),
3852
py::arg("context_ad"), py::arg("contact_geoms"), py::arg("options"))
3953
.def("GenerateLCS", &c3::multibody::LCSFactory::GenerateLCS)
40-
// .def("GetWitnessPointsAndForceBasisInWorldFrame",
41-
// &c3::multibody::LCSFactory::GetWitnessPointsAndForceBasisInWorldFrame)
54+
.def("GetContactDescriptions",
55+
&c3::multibody::LCSFactory::GetContactDescriptions)
4256
.def("UpdateStateAndInput",
4357
&c3::multibody::LCSFactory::UpdateStateAndInput, py::arg("state"),
4458
py::arg("input"))

bindings/pyc3/c3_systems_py.cc

Lines changed: 89 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@
99
#include "systems/c3_controller_options.h"
1010
#include "systems/framework/c3_output.h"
1111
#include "systems/framework/timestamped_vector.h"
12+
#include "systems/lcmt_generators/c3_output_generator.h"
13+
#include "systems/lcmt_generators/c3_trajectory_generator.h"
14+
#include "systems/lcmt_generators/contact_force_generator.h"
1215
#include "systems/lcs_factory_system.h"
1316
#include "systems/lcs_simulator.h"
1417

@@ -99,10 +102,10 @@ PYBIND11_MODULE(systems, m) {
99102
&LCSFactorySystem::get_input_port_lcs_input,
100103
py::return_value_policy::reference)
101104
.def("get_output_port_lcs", &LCSFactorySystem::get_output_port_lcs,
105+
py::return_value_policy::reference)
106+
.def("get_output_port_lcs_contact_description",
107+
&LCSFactorySystem::get_output_port_lcs_contact_description,
102108
py::return_value_policy::reference);
103-
// .def("get_output_port_lcs_contact_points_and_force_basis",
104-
// &LCSFactorySystem::get_output_port_lcs_contact_points_and_force_basis,
105-
// py::return_value_policy::reference);
106109

107110
py::class_<C3Output::C3Solution>(m, "C3Solution")
108111
.def(py::init<>())
@@ -157,7 +160,7 @@ PYBIND11_MODULE(systems, m) {
157160
drake::pydrake::AddValueInstantiation<c3::LCS>(m);
158161
drake::pydrake::AddValueInstantiation<C3Output::C3Solution>(m);
159162
drake::pydrake::AddValueInstantiation<C3Output::C3Intermediates>(m);
160-
163+
161164
py::class_<C3StatePredictionJoint>(m, "C3StatePredictionJoint")
162165
.def(py::init<>())
163166
.def_readwrite("name", &C3StatePredictionJoint::name)
@@ -178,6 +181,88 @@ PYBIND11_MODULE(systems, m) {
178181
&C3ControllerOptions::state_prediction_joints);
179182

180183
m.def("LoadC3ControllerOptions", &LoadC3ControllerOptions);
184+
185+
// C3OutputGenerator
186+
py::class_<lcmt_generators::C3OutputGenerator,
187+
drake::systems::LeafSystem<double>>(m, "C3OutputGenerator")
188+
.def(py::init<>())
189+
.def("get_input_port_c3_solution",
190+
&lcmt_generators::C3OutputGenerator::get_input_port_c3_solution,
191+
py::return_value_policy::reference)
192+
.def("get_input_port_c3_intermediates",
193+
&lcmt_generators::C3OutputGenerator::get_input_port_c3_intermediates,
194+
py::return_value_policy::reference)
195+
.def("get_output_port_c3_output",
196+
&lcmt_generators::C3OutputGenerator::get_output_port_c3_output,
197+
py::return_value_policy::reference)
198+
.def_static("AddLcmPublisherToBuilder",
199+
&lcmt_generators::C3OutputGenerator::AddLcmPublisherToBuilder,
200+
py::arg("builder"), py::arg("solution_port"),
201+
py::arg("intermediates_port"), py::arg("channel"),
202+
py::arg("lcm"), py::arg("publish_triggers"),
203+
py::arg("publish_period"), py::arg("publish_offset"));
204+
205+
// C3TrajectoryGenerator
206+
py::class_<lcmt_generators::TrajectoryDescription::index_range>(
207+
m, "TrajectoryDescriptionIndexRange")
208+
.def(py::init<>())
209+
.def_readwrite(
210+
"start", &lcmt_generators::TrajectoryDescription::index_range::start)
211+
.def_readwrite("end",
212+
&lcmt_generators::TrajectoryDescription::index_range::end);
213+
py::class_<lcmt_generators::TrajectoryDescription>(m, "TrajectoryDescription")
214+
.def(py::init<>())
215+
.def_readwrite("trajectory_name",
216+
&lcmt_generators::TrajectoryDescription::trajectory_name)
217+
.def_readwrite("variable_type",
218+
&lcmt_generators::TrajectoryDescription::variable_type)
219+
.def_readwrite("indices",
220+
&lcmt_generators::TrajectoryDescription::indices);
221+
py::class_<lcmt_generators::C3TrajectoryGeneratorConfig>(
222+
m, "C3TrajectoryGeneratorConfig")
223+
.def(py::init<>())
224+
.def_readwrite(
225+
"trajectories",
226+
&lcmt_generators::C3TrajectoryGeneratorConfig::trajectories);
227+
py::class_<lcmt_generators::C3TrajectoryGenerator,
228+
drake::systems::LeafSystem<double>>(m, "C3TrajectoryGenerator")
229+
.def(py::init<lcmt_generators::C3TrajectoryGeneratorConfig>())
230+
.def("get_input_port_c3_solution",
231+
&lcmt_generators::C3TrajectoryGenerator::get_input_port_c3_solution,
232+
py::return_value_policy::reference)
233+
.def("get_output_port_lcmt_c3_trajectory",
234+
&lcmt_generators::C3TrajectoryGenerator::
235+
get_output_port_lcmt_c3_trajectory,
236+
py::return_value_policy::reference)
237+
.def_static(
238+
"AddLcmPublisherToBuilder",
239+
&lcmt_generators::C3TrajectoryGenerator::AddLcmPublisherToBuilder,
240+
py::arg("builder"), py::arg("config"), py::arg("solution_port"),
241+
py::arg("channel"), py::arg("lcm"), py::arg("publish_triggers"),
242+
py::arg("publish_period"), py::arg("publish_offset"));
243+
244+
// ContactForceGenerator
245+
py::class_<lcmt_generators::ContactForceGenerator,
246+
drake::systems::LeafSystem<double>>(m, "ContactForceGenerator")
247+
.def(py::init<>())
248+
.def("get_input_port_c3_solution",
249+
&lcmt_generators::ContactForceGenerator::get_input_port_c3_solution,
250+
py::return_value_policy::reference)
251+
.def("get_input_port_lcs_contact_info",
252+
&lcmt_generators::ContactForceGenerator::
253+
get_input_port_lcs_contact_info,
254+
py::return_value_policy::reference)
255+
.def("get_output_port_contact_force",
256+
&lcmt_generators::ContactForceGenerator::
257+
get_output_port_contact_force,
258+
py::return_value_policy::reference)
259+
.def_static(
260+
"AddLcmPublisherToBuilder",
261+
&lcmt_generators::ContactForceGenerator::AddLcmPublisherToBuilder,
262+
py::arg("builder"), py::arg("solution_port"),
263+
py::arg("lcs_contact_info_port"), py::arg("channel"), py::arg("lcm"),
264+
py::arg("publish_triggers"), py::arg("publish_period"),
265+
py::arg("publish_offset"));
181266
}
182267
} // namespace pyc3
183268
} // namespace systems

core/BUILD.bazel

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,16 @@
33

44
package(default_visibility = ["//visibility:public"])
55

6+
cc_library(
7+
name = "core",
8+
visibility = ["//visibility:public"],
9+
deps = [
10+
":c3",
11+
":options",
12+
":lcs",
13+
],
14+
)
15+
616
cc_library(
717
name = "options",
818
hdrs = ["c3_options.h",

multibody/BUILD.bazel

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,15 @@
33

44
package(default_visibility = ["//visibility:public"])
55

6+
cc_library(
7+
name = "multibody",
8+
visibility = ["//visibility:public"],
9+
deps = [
10+
":lcs_factory",
11+
":options"
12+
],
13+
)
14+
615
cc_library(
716
name = "lcs_factory",
817
srcs = ["lcs_factory.cc",

systems/BUILD.bazel

Lines changed: 54 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -4,45 +4,80 @@
44
package(default_visibility = ["//visibility:public"])
55

66
cc_library(
7-
name = "vector",
7+
name = "systems",
8+
visibility = ["//visibility:public"],
9+
deps = [
10+
":framework",
11+
":c3_controller",
12+
":lcs_simulator",
13+
":lcs_factory_system",
14+
":lcmt_generators",
15+
]
16+
)
17+
18+
cc_library(
19+
name = "framework",
820
srcs = [
21+
"framework/c3_output.cc",
922
"framework/timestamped_vector.cc",
1023
],
1124
hdrs = [
25+
"framework/c3_output.h",
1226
"framework/timestamped_vector.h",
1327
],
1428
deps = [
29+
"//lcmtypes:lcmt_c3",
1530
"@drake//:drake_shared_library",
1631
],
1732
)
1833

19-
cc_library(
20-
name = "systems",
34+
cc_library( name = "c3_controller",
2135
srcs = [
2236
"c3_controller.cc",
23-
"lcs_simulator.cc",
24-
"framework/c3_output.cc",
25-
"lcs_factory_system.cc",
2637
],
2738
hdrs = [
2839
"c3_controller.h",
29-
"lcs_simulator.h",
30-
"framework/c3_output.h",
31-
"lcs_factory_system.h",
32-
33-
],
40+
],
3441
deps = [
35-
":vector",
3642
":options",
37-
":c3_output",
38-
":lcmt_generators",
43+
":framework",
3944
"//core:c3",
4045
"//core:options",
4146
"//multibody:lcs_factory",
4247
"@drake//:drake_shared_library",
4348
],
4449
)
4550

51+
cc_library( name = "lcs_simulator",
52+
srcs = [
53+
"lcs_simulator.cc",
54+
],
55+
hdrs = [
56+
"lcs_simulator.h",
57+
],
58+
deps = [
59+
"//core:lcs",
60+
"@drake//:drake_shared_library",
61+
],
62+
)
63+
64+
cc_library(
65+
name = "lcs_factory_system",
66+
srcs = [
67+
"lcs_factory_system.cc",
68+
],
69+
hdrs = [
70+
"lcs_factory_system.h",
71+
],
72+
deps = [
73+
":framework",
74+
"//core:lcs",
75+
"//core:options",
76+
"//multibody:lcs_factory",
77+
"@drake//:drake_shared_library",
78+
],
79+
)
80+
4681
cc_library(
4782
name = "options",
4883
hdrs = [
@@ -68,26 +103,13 @@ cc_library(
68103
"lcmt_generators/c3_trajectory_generator_config.h",
69104
],
70105
deps = [
71-
":c3_output",
106+
":framework",
72107
"//multibody:lcs_factory",
73108
"//lcmtypes:lcmt_c3",
74109
"@drake//:drake_shared_library",
75110
],
76111
)
77112

78-
cc_library(
79-
name = "c3_output",
80-
srcs = [
81-
"framework/c3_output.cc",
82-
],
83-
hdrs = [
84-
"framework/c3_output.h",
85-
],
86-
deps = [
87-
"//lcmtypes:lcmt_c3",
88-
"@drake//:drake_shared_library",
89-
]
90-
)
91113

92114
filegroup(
93115
name = 'test_data',
@@ -136,3 +158,7 @@ cc_library(
136158
"@drake//:drake_shared_library",
137159
],
138160
)
161+
162+
exports_files(glob(["**/*.h", "**/*.hpp"]),
163+
visibility = ["//visibility:public"],
164+
)

systems/lcmt_generators/c3_trajectory_generator.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ void C3TrajectoryGenerator::GenerateTrajectory(
6565
auto indices = traj_desc.indices;
6666
if (indices.empty()) {
6767
TrajectoryDescription::index_range default_indices = {
68-
.start = 0, .end = solution_values.rows() - 1};
68+
.start = 0, .end = (int)solution_values.rows() - 1};
6969
indices.push_back(default_indices);
7070
}
7171

systems/lcmt_generators/contact_force_generator.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ void ContactForceGenerator::DoCalc(const Context<double>& context,
5656
output->forces.clear();
5757
output->num_forces = 0;
5858
// Iterate over all contact points and compute forces.
59-
for (int i = 0; i < contact_info->size(); ++i) {
59+
for (size_t i = 0; i < contact_info->size(); ++i) {
6060
auto force = lcmt_contact_force();
6161

6262
if (contact_info->at(i).is_slack)

0 commit comments

Comments
 (0)