1
1
#include " pybind11/pybind11.h"
2
2
3
3
#include " drake/bindings/pydrake/pydrake_pybind.h"
4
+ #include " drake/bindings/pydrake/systems/systems_pybind.h"
4
5
#include " drake/systems/analysis/integrator_base.h"
5
6
#include " drake/systems/analysis/simulator.h"
6
7
@@ -15,44 +16,51 @@ PYBIND11_MODULE(analysis, m) {
15
16
16
17
m.doc () = " Bindings for the analysis portion of the Systems framework." ;
17
18
18
- using T = double ;
19
-
20
- py::class_<IntegratorBase<T>>(m, " IntegratorBase" )
21
- .def (" set_fixed_step_mode" , &IntegratorBase<T>::set_fixed_step_mode)
22
- .def (" get_fixed_step_mode" , &IntegratorBase<T>::get_fixed_step_mode)
23
- .def (" set_target_accuracy" , &IntegratorBase<T>::set_target_accuracy)
24
- .def (" get_target_accuracy" , &IntegratorBase<T>::get_target_accuracy)
25
- .def (" set_maximum_step_size" , &IntegratorBase<T>::set_maximum_step_size)
26
- .def (" get_maximum_step_size" , &IntegratorBase<T>::get_maximum_step_size)
27
- .def (" set_requested_minimum_step_size" ,
28
- &IntegratorBase<T>::set_requested_minimum_step_size)
29
- .def (" get_requested_minimum_step_size" ,
30
- &IntegratorBase<T>::get_requested_minimum_step_size)
31
- .def (" set_throw_on_minimum_step_size_violation" ,
32
- &IntegratorBase<T>::set_throw_on_minimum_step_size_violation)
33
- .def (" get_throw_on_minimum_step_size_violation" ,
34
- &IntegratorBase<T>::get_throw_on_minimum_step_size_violation);
35
-
36
- py::class_<Simulator<T>>(m, " Simulator" )
37
- .def (py::init<const System<T>&>(),
38
- // Keep alive, reference: `self` keeps `System` alive.
39
- py::keep_alive<1 , 2 >())
40
- .def (py::init<const System<T>&, unique_ptr<Context<T>>>(),
41
- // Keep alive, reference: `self` keeps `System` alive.
42
- py::keep_alive<1 , 2 >(),
43
- // Keep alive, ownership: `Context` keeps `self` alive.
44
- py::keep_alive<3 , 1 >())
45
- .def (" Initialize" , &Simulator<T>::Initialize)
46
- .def (" StepTo" , &Simulator<T>::StepTo)
47
- .def (" get_context" , &Simulator<T>::get_context, py_reference_internal)
48
- .def (" get_integrator" , &Simulator<T>::get_integrator, py_reference_internal)
49
- .def (" get_mutable_integrator" , &Simulator<T>::get_mutable_integrator,
50
- py_reference_internal)
51
- .def (" get_mutable_context" , &Simulator<T>::get_mutable_context,
52
- py_reference_internal)
53
- .def (" set_publish_every_time_step" ,
54
- &Simulator<T>::set_publish_every_time_step)
55
- .def (" set_target_realtime_rate" , &Simulator<T>::set_target_realtime_rate);
19
+ py::module::import (" pydrake.systems.framework" );
20
+
21
+ auto bind_scalar_types = [m](auto dummy) {
22
+ using T = decltype (dummy);
23
+ DefineTemplateClassWithDefault<IntegratorBase<T>>(
24
+ m, " IntegratorBase" , GetPyParam<T>())
25
+ .def (" set_fixed_step_mode" , &IntegratorBase<T>::set_fixed_step_mode)
26
+ .def (" get_fixed_step_mode" , &IntegratorBase<T>::get_fixed_step_mode)
27
+ .def (" set_target_accuracy" , &IntegratorBase<T>::set_target_accuracy)
28
+ .def (" get_target_accuracy" , &IntegratorBase<T>::get_target_accuracy)
29
+ .def (" set_maximum_step_size" , &IntegratorBase<T>::set_maximum_step_size)
30
+ .def (" get_maximum_step_size" , &IntegratorBase<T>::get_maximum_step_size)
31
+ .def (" set_requested_minimum_step_size" ,
32
+ &IntegratorBase<T>::set_requested_minimum_step_size)
33
+ .def (" get_requested_minimum_step_size" ,
34
+ &IntegratorBase<T>::get_requested_minimum_step_size)
35
+ .def (" set_throw_on_minimum_step_size_violation" ,
36
+ &IntegratorBase<T>::set_throw_on_minimum_step_size_violation)
37
+ .def (" get_throw_on_minimum_step_size_violation" ,
38
+ &IntegratorBase<T>::get_throw_on_minimum_step_size_violation);
39
+
40
+ DefineTemplateClassWithDefault<Simulator<T>>(
41
+ m, " Simulator" , GetPyParam<T>())
42
+ .def (py::init<const System<T>&>(),
43
+ // Keep alive, reference: `self` keeps `System` alive.
44
+ py::keep_alive<1 , 2 >())
45
+ .def (py::init<const System<T>&, unique_ptr<Context<T>>>(),
46
+ // Keep alive, reference: `self` keeps `System` alive.
47
+ py::keep_alive<1 , 2 >(),
48
+ // Keep alive, ownership: `Context` keeps `self` alive.
49
+ py::keep_alive<3 , 1 >())
50
+ .def (" Initialize" , &Simulator<T>::Initialize)
51
+ .def (" StepTo" , &Simulator<T>::StepTo)
52
+ .def (" get_context" , &Simulator<T>::get_context, py_reference_internal)
53
+ .def (" get_integrator" , &Simulator<T>::get_integrator,
54
+ py_reference_internal)
55
+ .def (" get_mutable_integrator" , &Simulator<T>::get_mutable_integrator,
56
+ py_reference_internal)
57
+ .def (" get_mutable_context" , &Simulator<T>::get_mutable_context,
58
+ py_reference_internal)
59
+ .def (" set_publish_every_time_step" ,
60
+ &Simulator<T>::set_publish_every_time_step)
61
+ .def (" set_target_realtime_rate" , &Simulator<T>::set_target_realtime_rate);
62
+ };
63
+ type_visit (bind_scalar_types, pysystems::NonSymbolicScalarPack{});
56
64
}
57
65
58
66
} // namespace pydrake
0 commit comments