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
0 commit comments