Go to the documentation of this file.
    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());
 
   70                                          const std::string& 
name) {
 
   92   bp::enum_<LoggerVerbosity>(
"LoggerVerbosity")
 
  100   bp::class_<Entity, boost::noncopyable>(
"Entity", bp::no_init)
 
  101       .add_property(
"name",
 
  104                         bp::return_value_policy<bp::copy_const_reference>()))
 
  105       .add_property(
"className",
 
  108                         bp::return_value_policy<bp::copy_const_reference>()),
 
  109                     "the class name of the Entity")
 
  116                     "the verbosity level of the entity")
 
  121                     "the time sample for printing debugging information")
 
  126                     "set the period at which debugging information are printed")
 
  130           +[](
const Entity& e) -> std::string {
 
  131             std::ostringstream os;
 
  137           +[](
const Entity& e) -> bp::list {
 
  139             for (
auto& el : e.
getSignalMap()) ret.append(bp::ptr(el.second));
 
  142           "Return the list of signals.")
 
  147            "get signal by name from an Entity", bp::arg(
"name"))
 
  149            "return True if the entity has a signal with the given name")
 
  155             std::cout << 
"--- <" << e.
getName();
 
  157               std::cout << 
"> has no signal\n";
 
  159               std::cout << 
"> signal list:\n";
 
  160             for (
const auto& el : signals)
 
  161               el.second->display(std::cout << 
"    |-- <") << 
'\n';
 
  163           "Print the list of signals into standard output: temporary.")
 
  207       .add_static_property(
 
  211   python::exposeEntity<PythonEntity, bp::bases<Entity>, 0>()
 
  215   python::exposeEntity<python::PythonSignalContainer, bp::bases<Entity>, 0>()
 
  217            "Remove a signal", bp::arg(
"signal_name"));
 
  221   using dg::command::Command;
 
  222   bp::class_<Command, boost::noncopyable>(
"Command", bp::no_init)
 
  224            "execute the command")
 
  225       .add_property(
"__doc__", &Command::getDocstring);
 
  230           "plug an output signal into an input signal",
 
  231           (bp::arg(
"signalOut"), 
"signalIn"));
 
  233           "Enable or disable tracing debug info in a file");
 
  235   bp::def(
"create_signal_wrapper",
 
  239   bp::def(
"factory_get_entity_class_list",
 
  241           "return the list of entity classes");
 
  243           "Write the graph of entities in a filename.");
 
  245           "return the list of instanciated entities");
 
  246   bp::def(
"addLoggerFileOutputStream",
 
  248           "add a output file stream to the logger by filename");
 
  249   bp::def(
"addLoggerCoutOutputStream",
 
  251           "add std::cout as output stream to the logger");
 
  252   bp::def(
"closeLoggerFileOutputStream",
 
  254           "close all the loggers file output streams.");
 
  255   bp::def(
"real_time_logger_destroy",
 
  257           "Destroy the real time logger.");
 
  258   bp::def(
"real_time_logger_spin_once",
 
  260           "Destroy the real time logger.");
 
  261   bp::def(
"real_time_logger_instance",
 
  263           "Starts the real time logger.");
 
  269   if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
 
  271   if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
 
  274   eigenpy::enableEigenPySpecific<Eigen::Matrix4d>();
 
  287   bp::class_<MapOfEntities>(
"MapOfEntities")
 
  288       .def(
"__len__", &MapOfEntities::size)
 
  293             for (
const auto& el : m) 
res.append(el.first);
 
  294             return bp::tuple(
res);
 
  300             for (
const auto& el : m) 
res.append(bp::ptr(el.second));
 
  301             return bp::tuple(
res);
 
  310       .def(
"__iter__", bp::iterator<MapOfEntities>())
 
  316   bp::to_python_converter<MapOfEntities::value_type,
 
  
void EIGENPY_DLLAPI exposeAngleAxis()
bool hasSignal(const std::string &signame) const
void realTimeLoggerSpinOnce()
void EIGENPY_DLLAPI exposeQuaternion()
bp::return_value_policy< bp::manage_new_object > manage_new_object
void EIGENPY_DLLAPI enableEigenPy()
void closeLoggerFileOutputStream()
dg::SignalBase< dg::sigtime_t > * getSignal(dg::Entity &e, const std::string &name)
static void closeFile(const char *filename=DEBUG_FILENAME_DEFAULT)
void enableTrace(bool enable, const char *filename)
bool setStreamPrintPeriod(double t)
SignalMap getSignalMap() const
VERBOSITY_INFO_WARNING_ERROR
void addLoggerCoutOutputStream()
virtual std::string getDocString() const
void addLoggerFileOutputStream(const char *filename)
bp::object executeCmd(bp::tuple args, bp::dict)
std::map< std::string, SignalBase< sigtime_t > * > SignalMap
const std::string & getName() const
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(PythonEntity, "PythonEntity")
BOOST_PYTHON_MODULE(wrap)
static PyObject * convert(const MapOfEntities::value_type &pair)
SignalBase< sigtime_t > * createSignalWrapper(const char *name, const char *type, bp::object object)
Create an instance of SignalWrapper.
DYNAMIC_GRAPH_ENTITY_DECL()
void signalRegistration(dg::SignalBase< dg::sigtime_t > &signal)
bool setTimeSample(double t)
virtual const std::string & getClassName() const
virtual void plug(SignalBase< sigtime_t > *sigarg)
virtual void display(std::ostream &os) const
bp::tuple getEntityClassList()
Get name of entity.
void realTimeLoggerDestroy()
Entity(const std::string &name)
const Entities & getEntityMap() const
void rmSignal(const std::string &name)
void signalDeregistration(const std::string &name)
std::map< std::string, Entity * > Entities
static PoolStorage * getInstance()
void realTimeLoggerInstance()
bp::list getEntityList()
Get list of entities.
SignalBase< sigtime_t > & getSignal(const std::string &signalName)
dg::PoolStorage::Entities MapOfEntities
static void openFile(const char *filename=DEBUG_FILENAME_DEFAULT)
void plug(SignalBase< sigtime_t > *signalOut, SignalBase< sigtime_t > *signalIn)
plug a signal into another one.
MapOfEntities * getEntityMap()
bp::return_value_policy< bp::reference_existing_object > reference_existing_object
double getStreamPrintPeriod()
void signalDeregistration(const std::string &name)
void writeGraph(const char *filename)
void signalRegistration(const SignalArray< sigtime_t > &signals)
void setLoggerVerbosityLevel(LoggerVerbosity lv)
LoggerVerbosity getLoggerVerbosityLevel()
dynamic-graph-python
Author(s): Nicolas Mansard, Olivier Stasse
autogenerated on Fri Oct 27 2023 02:16:36