7 #include <dynamic-graph/entity.h> 9 #include <dynamic-graph/factory.h> 10 #include <dynamic-graph/pool.h> 13 #include <dynamic-graph/signal.h> 16 #include <Eigen/Geometry> 17 #include <boost/python.hpp> 18 #include <boost/python/raw_function.hpp> 19 #include <boost/python/suite/indexing/map_indexing_suite.hpp> 36 signalIn->
plug(signalOut);
53 typedef bp::return_value_policy<bp::reference_existing_object>
59 static PyObject*
convert(
const MapOfEntities::value_type& pair) {
60 return bp::incref(bp::make_tuple(pair.first, bp::ptr(pair.second)).ptr());
91 bp::enum_<LoggerVerbosity>(
"LoggerVerbosity")
99 bp::class_<Entity, boost::noncopyable>(
"Entity", bp::no_init)
100 .add_property(
"name",
103 bp::return_value_policy<bp::copy_const_reference>()))
104 .add_property(
"className",
107 bp::return_value_policy<bp::copy_const_reference>()),
108 "the class name of the Entity")
115 "the verbosity level of the entity")
120 "the time sample for printing debugging information")
125 "set the period at which debugging information are printed")
129 +[](
const Entity& e) -> std::string {
130 std::ostringstream os;
136 +[](
const Entity& e) -> bp::list {
138 for (
auto& el : e.
getSignalMap()) ret.append(bp::ptr(el.second));
141 "Return the list of signals.")
146 "get signal by name from an Entity", bp::arg(
"name"))
148 "return True if the entity has a signal with the given name")
154 std::cout <<
"--- <" << e.
getName();
156 std::cout <<
"> has no signal\n";
158 std::cout <<
"> signal list:\n";
159 for (
const auto& el : signals)
160 el.second->display(std::cout <<
" |-- <") <<
'\n';
162 "Print the list of signals into standard output: temporary.")
206 .add_static_property(
210 python::exposeEntity<PythonEntity, bp::bases<Entity>, 0>()
214 python::exposeEntity<python::PythonSignalContainer, bp::bases<Entity>, 0>()
216 "Remove a signal", bp::arg(
"signal_name"));
220 using dg::command::Command;
221 bp::class_<Command, boost::noncopyable>(
"Command", bp::no_init)
223 "execute the command")
224 .add_property(
"__doc__", &Command::getDocstring);
229 "plug an output signal into an input signal",
230 (bp::arg(
"signalOut"),
"signalIn"));
232 "Enable or disable tracing debug info in a file");
234 bp::def(
"create_signal_wrapper",
238 bp::def(
"factory_get_entity_class_list",
240 "return the list of entity classes");
242 "Write the graph of entities in a filename.");
244 "return the list of instanciated entities");
245 bp::def(
"addLoggerFileOutputStream",
247 "add a output file stream to the logger by filename");
248 bp::def(
"addLoggerCoutOutputStream",
250 "add std::cout as output stream to the logger");
251 bp::def(
"closeLoggerFileOutputStream",
253 "close all the loggers file output streams.");
254 bp::def(
"real_time_logger_destroy",
256 "Destroy the real time logger.");
257 bp::def(
"real_time_logger_spin_once",
259 "Destroy the real time logger.");
260 bp::def(
"real_time_logger_instance",
262 "Starts the real time logger.");
268 if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
270 if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
273 eigenpy::enableEigenPySpecific<Eigen::Matrix4d>();
286 bp::class_<MapOfEntities>(
"MapOfEntities")
287 .def(
"__len__", &MapOfEntities::size)
290 +[](
const MapOfEntities& m) -> bp::tuple {
292 for (
const auto& el : m) res.append(el.first);
293 return bp::tuple(res);
297 +[](
const MapOfEntities& m) -> bp::tuple {
299 for (
const auto& el : m) res.append(bp::ptr(el.second));
300 return bp::tuple(res);
303 static_cast<dg::Entity*& (MapOfEntities::*)(
const std::string& k)
>(
307 "__setitem__", +[](MapOfEntities& m,
const std::string& n,
309 .def(
"__iter__", bp::iterator<MapOfEntities>())
312 +[](
const MapOfEntities& m,
const std::string& n) ->
bool {
315 bp::to_python_converter<MapOfEntities::value_type,
void EIGENPY_DLLAPI exposeQuaternion()
virtual std::string getDocString() const
bool hasSignal(const std::string &signame) const
void closeLoggerFileOutputStream()
void addLoggerFileOutputStream(const char *filename)
void signalRegistration(const SignalArray< int > &signals)
SignalMap getSignalMap() const
bool setTimeSample(double t)
static PyObject * convert(const MapOfEntities::value_type &pair)
void signalRegistration(dg::SignalBase< int > &signal)
void signalDeregistration(const std::string &name)
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(PythonSignalContainer, "PythonSignalContainer")
BOOST_PYTHON_MODULE(wrap)
void EIGENPY_DLLAPI enableEigenPy()
void addLoggerCoutOutputStream()
static void openFile(const char *filename=DEBUG_FILENAME_DEFAULT)
std::map< std::string, SignalBase< int > *> SignalMap
MapOfEntities * getEntityMap()
static void closeFile(const char *filename=DEBUG_FILENAME_DEFAULT)
dg::SignalBase< int > * getSignal(dg::Entity &e, const std::string &name)
virtual const std::string & getClassName() const
void realTimeLoggerDestroy()
bp::return_value_policy< bp::reference_existing_object > reference_existing_object
bp::object executeCmd(bp::tuple args, bp::dict)
#define DYNAMIC_GRAPH_ENTITY_DECL()
virtual void display(std::ostream &os) const
void plug(SignalBase< int > *signalOut, SignalBase< int > *signalIn)
plug a signal into another one.
void rmSignal(const std::string &name)
static PoolStorage * getInstance()
double getStreamPrintPeriod()
void setLoggerVerbosityLevel(LoggerVerbosity lv)
Entity(const std::string &name)
void realTimeLoggerInstance()
dg::PoolStorage::Entities MapOfEntities
virtual void plug(SignalBase< Time > *sigarg)
bp::tuple getEntityClassList()
Get name of entity.
LoggerVerbosity getLoggerVerbosityLevel()
void enableTrace(bool enable, const char *filename)
const std::string & getName() const
std::map< std::string, Entity *> Entities
const Entities & getEntityMap() const
VERBOSITY_INFO_WARNING_ERROR
bp::return_value_policy< bp::manage_new_object > manage_new_object
SignalBase< int > & getSignal(const std::string &signalName)
void writeGraph(const char *filename)
bp::list getEntityList()
Get list of entities.
bool setStreamPrintPeriod(double t)
void signalDeregistration(const std::string &name)
void realTimeLoggerSpinOnce()
SignalBase< int > * createSignalWrapper(const char *name, const char *type, bp::object object)
Create an instance of SignalWrapper.
void EIGENPY_DLLAPI exposeAngleAxis()