Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • ostasse/dynamic-graph-python
  • gsaurel/dynamic-graph-python
  • stack-of-tasks/dynamic-graph-python
3 results
Show changes
Showing
with 989 additions and 1256 deletions
......@@ -9,6 +9,8 @@
# >>> e.a.b.c.d( ...)
# as if it was a classical member function of e.
from __future__ import print_function
class CommandPath(object):
"""
......@@ -16,10 +18,11 @@ class CommandPath(object):
to store entity commands. It has no members except those automatically
defined at run time (which should be CommandPath or functions).
"""
mother = None
def __getattr__(self, name):
privateName = name + '_obj'
privateName = name + "_obj"
if privateName in self.__dict__:
obj = getattr(self, privateName)
obj.mother = self.mother
......@@ -36,7 +39,7 @@ def createCommandModule(target, name):
return __
privateName = name + '_obj'
privateName = name + "_obj"
setattr(target, privateName, CommandPath())
if not isinstance(target, CommandPath):
......@@ -44,8 +47,8 @@ def createCommandModule(target, name):
class CommandLauncher(object):
"""
"""
""" """
mother = None
fun = None
......@@ -58,7 +61,7 @@ class CommandLauncher(object):
def createCommandLauncher(target, name, fun):
if isinstance(target, CommandPath):
privateName = name + '_obj'
privateName = name + "_obj"
setattr(target, privateName, CommandLauncher(fun))
else:
setattr(target, name, fun)
......@@ -72,7 +75,7 @@ def setattrpath(target, path, attribute):
pathk = target
read = True
if isinstance(path, str):
path = path.split('.')
path = path.split(".")
for tokenk in path[0:-1]:
if (not read) | (tokenk not in pathk.__dict__):
read = False
......@@ -92,7 +95,7 @@ def getattrpath(target, path):
"""
pathk = target
if isinstance(path, str):
path = path.split('.')
path = path.split(".")
for tokenk in path:
privateName = tokenk + "_obj"
if hasattr(pathk, privateName):
......@@ -101,7 +104,12 @@ def getattrpath(target, path):
if hasattr(pathk, tokenk):
pathk = getattr(pathk, tokenk)
else:
raise Exception('Path does not exist -- while accessing "' + tokenk + '" in ' + '.'.join(path))
raise Exception(
'Path does not exist -- while accessing "'
+ tokenk
+ '" in '
+ ".".join(path)
)
return pathk
......@@ -112,11 +120,11 @@ def existattrpath(target, path):
"""
pathk = target
if isinstance(path, str):
path = path.split('.')
path = path.split(".")
for tokenk in path[0:-1]:
print('check ', tokenk)
print("check ", tokenk)
privateName = tokenk + "_obj"
if (privateName not in pathk.__dict__):
if privateName not in pathk.__dict__:
return False
pathk = getattr(pathk, privateName)
name = path[-1]
......
// Copyright 2010, Florent Lamiraux, Thomas Moulard, LAAS-CNRS.
#include "dynamic-graph/python/convert-dg-to-py.hh"
#include <dynamic-graph/signal-base.h>
#include <dynamic-graph/signal-caster.h>
#include <dynamic-graph/signal.h>
#include <boost/python.hpp>
#include <boost/python/stl_iterator.hpp>
#include <iostream>
#include <sstream>
#include "dynamic-graph/python/python-compat.hh"
namespace dynamicgraph {
using ::dynamicgraph::SignalBase;
namespace python {
namespace convert {
namespace bp = boost::python;
command::Value toValue(bp::object o, const command::Value::Type& valueType) {
using command::Value;
switch (valueType) {
case (Value::BOOL):
return Value(bp::extract<bool>(o));
case (Value::UNSIGNED):
return Value(bp::extract<unsigned>(o));
case (Value::INT):
return Value(bp::extract<int>(o));
case (Value::FLOAT):
return Value(bp::extract<float>(o));
case (Value::DOUBLE):
return Value(bp::extract<double>(o));
case (Value::STRING):
return Value(bp::extract<std::string>(o));
case (Value::VECTOR):
// TODO for backward compatibility, support tuple or list ?
// I don't think so
return Value(bp::extract<Vector>(o));
case (Value::MATRIX):
// TODO for backward compatibility, support tuple or list ?
// I don't think so
return Value(bp::extract<Matrix>(o));
case (Value::MATRIX4D):
return Value(bp::extract<Eigen::Matrix4d>(o));
case (Value::VALUES):
// TODO the vector of values cannot be built since
// - the value type inside the vector are not know
// - inferring the value type from the Python type is not implemented.
throw std::invalid_argument(
"not implemented: cannot create a vector of values");
break;
default:
std::cerr << "Only int, double and string are supported." << std::endl;
}
return Value();
}
bp::object fromValue(const command::Value& value) {
using command::Value;
switch (value.type()) {
case (Value::BOOL):
return bp::object(value.boolValue());
case (Value::UNSIGNED):
return bp::object(value.unsignedValue());
case (Value::INT):
return bp::object(value.intValue());
case (Value::FLOAT):
return bp::object(value.floatValue());
case (Value::DOUBLE):
return bp::object(value.doubleValue());
case (Value::STRING):
return bp::object(value.stringValue());
case (Value::VECTOR):
return bp::object(value.vectorValue());
case (Value::MATRIX):
return bp::object(value.matrixXdValue());
case (Value::MATRIX4D):
return bp::object(value.matrix4dValue());
case (Value::VALUES): {
bp::list list;
for (const Value& v : value.constValuesValue()) list.append(fromValue(v));
return list;
}
case (Value::NONE):
default:
return bp::object();
}
}
} // namespace convert
} // namespace python
} // namespace dynamicgraph
// Copyright 2019, Olivier Stasse, LAAS-CNRS.
//
// See LICENSE
#include <iostream>
#define ENABLE_RT_LOG
#include <dynamic-graph/entity.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/real-time-logger.h>
#include <boost/shared_ptr.hpp>
#include <map>
#include <vector>
#include "dynamic-graph/python/dynamic-graph-py.hh"
typedef boost::shared_ptr<std::ofstream> ofstreamShrPtr;
namespace dynamicgraph {
namespace python {
namespace debug {
std::map<std::string, ofstreamShrPtr> mapOfFiles_;
void addLoggerFileOutputStream(const char* filename) {
std::ofstream* aofs = new std::ofstream;
ofstreamShrPtr ofs_shrptr = boost::shared_ptr<std::ofstream>(aofs);
aofs->open(filename, std::ofstream::out);
dynamicgraph::RealTimeLogger::instance();
dgADD_OSTREAM_TO_RTLOG(*aofs);
dgRTLOG() << "Added " << filename << " as an output stream \n";
mapOfFiles_[filename] = ofs_shrptr;
}
void closeLoggerFileOutputStream() {
for (const auto& el : mapOfFiles_) el.second->close();
}
void addLoggerCoutOutputStream() { dgADD_OSTREAM_TO_RTLOG(std::cout); }
void realTimeLoggerDestroy() { RealTimeLogger::destroy(); }
void realTimeLoggerSpinOnce() { RealTimeLogger::instance().spinOnce(); }
void realTimeLoggerInstance() { RealTimeLogger::instance(); }
} // namespace debug
} // namespace python
} // namespace dynamicgraph
// Copyright 2010, Florent Lamiraux, Thomas Moulard, LAAS-CNRS.
#include "dynamic-graph/python/dynamic-graph-py.hh"
#include <dynamic-graph/command.h>
#include <dynamic-graph/debug.h>
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/signal-base.h>
#include <dynamic-graph/signal-time-dependent.h>
#include <dynamic-graph/signal.h>
#include <dynamic-graph/tracer.h>
#include <Eigen/Geometry>
#include <boost/python.hpp>
#include <boost/python/raw_function.hpp>
#include <boost/python/suite/indexing/map_indexing_suite.hpp>
#include <eigenpy/eigenpy.hpp>
#include <eigenpy/geometry.hpp>
#include <iostream>
#include <sstream>
#include "dynamic-graph/python/convert-dg-to-py.hh"
#include "dynamic-graph/python/module.hh"
#include "dynamic-graph/python/signal-wrapper.hh"
namespace dynamicgraph {
namespace python {
/**
\brief plug a signal into another one.
*/
void plug(SignalBase<int>* signalOut, SignalBase<int>* signalIn) {
signalIn->plug(signalOut);
}
void enableTrace(bool enable, const char* filename) {
if (enable)
DebugTrace::openFile(filename);
else
DebugTrace::closeFile(filename);
}
} // namespace python
} // namespace dynamicgraph
namespace bp = boost::python;
namespace dg = dynamicgraph;
typedef bp::return_value_policy<bp::manage_new_object> manage_new_object;
typedef bp::return_value_policy<bp::reference_existing_object>
reference_existing_object;
typedef dg::PoolStorage::Entities MapOfEntities;
struct MapOfEntitiesPairToPythonConverter {
static PyObject* convert(const MapOfEntities::value_type& pair) {
return bp::incref(bp::make_tuple(pair.first, bp::ptr(pair.second)).ptr());
}
};
MapOfEntities* getEntityMap() {
return const_cast<MapOfEntities*>(
&dg::PoolStorage::getInstance()->getEntityMap());
}
dg::SignalBase<int>* getSignal(dg::Entity& e, const std::string& name) {
return &e.getSignal(name);
}
class PythonEntity : public dg::Entity {
DYNAMIC_GRAPH_ENTITY_DECL();
public:
using dg::Entity::Entity;
void signalRegistration(dg::SignalBase<int>& signal) {
dg::Entity::signalRegistration(signal);
}
void signalDeregistration(const std::string& name) {
dg::Entity::signalDeregistration(name);
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(PythonEntity, "PythonEntity");
void exposeEntityBase() {
using namespace dynamicgraph;
bp::enum_<LoggerVerbosity>("LoggerVerbosity")
.value("VERBOSITY_ALL", VERBOSITY_ALL)
.value("VERBOSITY_INFO_WARNING_ERROR", VERBOSITY_INFO_WARNING_ERROR)
.value("VERBOSITY_WARNING_ERROR", VERBOSITY_WARNING_ERROR)
.value("VERBOSITY_ERROR", VERBOSITY_ERROR)
.value("VERBOSITY_NONE", VERBOSITY_NONE)
.export_values();
bp::class_<Entity, boost::noncopyable>("Entity", bp::no_init)
.add_property("name",
bp::make_function(
&Entity::getName,
bp::return_value_policy<bp::copy_const_reference>()))
.add_property("className",
bp::make_function(
&Entity::getClassName,
bp::return_value_policy<bp::copy_const_reference>()),
"the class name of the Entity")
.add_property("__doc__", &Entity::getDocString)
.def("setLoggerVerbosityLevel", &Entity::setLoggerVerbosityLevel)
.def("getLoggerVerbosityLevel", &Entity::getLoggerVerbosityLevel)
.add_property("loggerVerbosityLevel", &Entity::setLoggerVerbosityLevel,
&Entity::getLoggerVerbosityLevel,
"the verbosity level of the entity")
.def("setTimeSample", &Entity::setTimeSample)
.def("getTimeSample", &Entity::getTimeSample)
.add_property("timeSample", &Entity::getTimeSample,
&Entity::setTimeSample,
"the time sample for printing debugging information")
.def("setStreamPrintPeriod", &Entity::setStreamPrintPeriod)
.def("getStreamPrintPeriod", &Entity::getStreamPrintPeriod)
.add_property("streamPrintPeriod", &Entity::getStreamPrintPeriod,
&Entity::setStreamPrintPeriod,
"set the period at which debugging information are printed")
.def(
"__str__",
+[](const Entity& e) -> std::string {
std::ostringstream os;
e.display(os);
return os.str();
})
.def(
"signals",
+[](const Entity& e) -> bp::list {
bp::list ret;
for (auto& el : e.getSignalMap()) ret.append(bp::ptr(el.second));
return ret;
},
"Return the list of signals.")
//.def("signal", +[](Entity& e, const std::string &name) { return
//&e.getSignal(name); },
// reference_existing_object())
.def("signal", &getSignal, reference_existing_object(),
"get signal by name from an Entity", bp::arg("name"))
.def("hasSignal", &Entity::hasSignal,
"return True if the entity has a signal with the given name")
.def(
"displaySignals",
+[](const Entity& e) {
Entity::SignalMap signals(e.getSignalMap());
std::cout << "--- <" << e.getName();
if (signals.empty())
std::cout << "> has no signal\n";
else
std::cout << "> signal list:\n";
for (const auto& el : signals)
el.second->display(std::cout << " |-- <") << '\n';
},
"Print the list of signals into standard output: temporary.")
/*
.def("__getattr__", +[](Entity& e, const std::string &name) ->
SignalBase<int>* { return &e.getSignal(name); },
reference_existing_object())
def __getattr__(self, name):
try:
return self.signal(name)
except Exception:
try:
object.__getattr__(self, name)
except AttributeError:
raise AttributeError("'%s' entity has no attribute %s\n" %
(self.name, name) + ' entity attributes are usually either\n' + ' -
commands,\n' + ' - signals or,\n' + ' - user defined attributes')
*/
/*
.def("__setattr__", +[](bp::object self, const std::string &name,
bp::object value) { Entity& e = bp::extract<Entity&> (self); if
(e.hasSignal(name)) throw std::invalid_argument(name + " already
designates a signal. " "It is not advised to set a new attribute of the
same name.");
// TODO How do you do that ? I am sure it is possible.
//object.__setattr__(self, name, value)
})
*/
/* TODO ?
def boundNewCommand(self, cmdName):
"""
At construction, all existing commands are bound directly in the
class. This method enables to bound new commands dynamically. These new
bounds are not made with the class, but directly with the object instance.
"""
def boundAllNewCommands(self):
"""
For all commands that are not attribute of the object instance nor of
the class, a new attribute of the instance is created to bound the
command.
"""
*/
// For backward compat
.add_static_property(
"entities",
bp::make_function(&getEntityMap, reference_existing_object()));
python::exposeEntity<PythonEntity, bp::bases<Entity>, 0>()
.def("signalRegistration", &PythonEntity::signalRegistration)
.def("signalDeregistration", &PythonEntity::signalDeregistration);
python::exposeEntity<python::PythonSignalContainer, bp::bases<Entity>, 0>()
.def("rmSignal", &python::PythonSignalContainer::rmSignal,
"Remove a signal", bp::arg("signal_name"));
}
void exposeCommand() {
using dg::command::Command;
bp::class_<Command, boost::noncopyable>("Command", bp::no_init)
.def("__call__", bp::raw_function(dg::python::entity::executeCmd, 1),
"execute the command")
.add_property("__doc__", &Command::getDocstring);
}
void exposeOldAPI() {
bp::def("plug", dynamicgraph::python::plug,
"plug an output signal into an input signal",
(bp::arg("signalOut"), "signalIn"));
bp::def("enableTrace", dynamicgraph::python::enableTrace,
"Enable or disable tracing debug info in a file");
// Signals
bp::def("create_signal_wrapper",
dynamicgraph::python::signalBase::createSignalWrapper,
reference_existing_object(), "create a SignalWrapper C++ object");
// Entity
bp::def("factory_get_entity_class_list",
dynamicgraph::python::factory::getEntityClassList,
"return the list of entity classes");
bp::def("writeGraph", dynamicgraph::python::pool::writeGraph,
"Write the graph of entities in a filename.");
bp::def("get_entity_list", dynamicgraph::python::pool::getEntityList,
"return the list of instanciated entities");
bp::def("addLoggerFileOutputStream",
dynamicgraph::python::debug::addLoggerFileOutputStream,
"add a output file stream to the logger by filename");
bp::def("addLoggerCoutOutputStream",
dynamicgraph::python::debug::addLoggerCoutOutputStream,
"add std::cout as output stream to the logger");
bp::def("closeLoggerFileOutputStream",
dynamicgraph::python::debug::closeLoggerFileOutputStream,
"close all the loggers file output streams.");
bp::def("real_time_logger_destroy",
dynamicgraph::python::debug::realTimeLoggerDestroy,
"Destroy the real time logger.");
bp::def("real_time_logger_spin_once",
dynamicgraph::python::debug::realTimeLoggerSpinOnce,
"Destroy the real time logger.");
bp::def("real_time_logger_instance",
dynamicgraph::python::debug::realTimeLoggerInstance,
"Starts the real time logger.");
}
void enableEigenPy() {
eigenpy::enableEigenPy();
if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
eigenpy::exposeQuaternion();
if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
eigenpy::exposeAngleAxis();
eigenpy::enableEigenPySpecific<Eigen::Matrix4d>();
}
BOOST_PYTHON_MODULE(wrap) {
enableEigenPy();
exposeOldAPI();
dg::python::exposeSignals();
exposeEntityBase();
exposeCommand();
typedef dg::PoolStorage::Entities MapOfEntities;
bp::class_<MapOfEntities>("MapOfEntities")
.def("__len__", &MapOfEntities::size)
.def(
"keys",
+[](const MapOfEntities& m) -> bp::tuple {
bp::list res;
for (const auto& el : m) res.append(el.first);
return bp::tuple(res);
})
.def(
"values",
+[](const MapOfEntities& m) -> bp::tuple {
bp::list res;
for (const auto& el : m) res.append(bp::ptr(el.second));
return bp::tuple(res);
})
.def("__getitem__",
static_cast<dg::Entity*& (MapOfEntities::*)(const std::string& k)>(
&MapOfEntities::at),
reference_existing_object())
.def(
"__setitem__", +[](MapOfEntities& m, const std::string& n,
dg::Entity* e) { m.emplace(n, e); })
.def("__iter__", bp::iterator<MapOfEntities>())
.def(
"__contains__",
+[](const MapOfEntities& m, const std::string& n) -> bool {
return m.count(n);
});
bp::to_python_converter<MapOfEntities::value_type,
MapOfEntitiesPairToPythonConverter>();
}
// Copyright 2010, Florent Lamiraux, Thomas Moulard, LAAS-CNRS.
#include <dynamic-graph/command.h>
#include <dynamic-graph/entity.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/linear-algebra.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/value.h>
#include <iostream>
#include "dynamic-graph/python/convert-dg-to-py.hh"
#include "dynamic-graph/python/dynamic-graph-py.hh"
// Ignore "dereferencing type-punned pointer will break strict-aliasing rules"
// warnings on gcc caused by Py_RETURN_TRUE and Py_RETURN_FALSE.
#if (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 2))
#pragma GCC diagnostic ignored "-Wstrict-aliasing"
#endif
namespace bp = boost::python;
using dynamicgraph::Entity;
using dynamicgraph::Matrix;
using dynamicgraph::SignalBase;
using dynamicgraph::Vector;
using dynamicgraph::command::Command;
using dynamicgraph::command::Value;
namespace dynamicgraph {
namespace python {
using namespace convert;
namespace entity {
/// \param obj an Entity object
void addCommands(bp::object obj) {
Entity& entity = bp::extract<Entity&>(obj);
for (const auto& el : entity.getNewStyleCommandMap())
obj.attr(el.first.c_str()) = bp::object(bp::ptr(el.second));
}
/// \param obj an Entity object
void addSignals(bp::object obj) {
Entity& entity = bp::extract<Entity&>(obj);
for (const auto& el : entity.getSignalMap())
// obj.attr(el.first.c_str()) = bp::make_function(
//+[&entity,el]() { return &entity.getSignal(el.first); },
// bp::return_value_policy<bp::reference_existing_object>());
obj.attr(el.first.c_str()) = bp::object(bp::ptr(el.second));
}
/**
\brief Create an instance of Entity
*/
Entity* create(const char* className, const char* instanceName) {
Entity* obj = NULL;
/* Try to find if the corresponding object already exists. */
if (dynamicgraph::PoolStorage::getInstance()->existEntity(instanceName,
obj)) {
if (obj->getClassName() != className) {
throw std::invalid_argument("Found an object named " +
std::string(instanceName) +
",\n"
"but this object is of type " +
std::string(obj->getClassName()) +
" and not " + std::string(className));
}
} else /* If not, create a new object. */
{
obj = dynamicgraph::FactoryStorage::getInstance()->newEntity(
std::string(className), std::string(instanceName));
}
return obj;
}
bp::object executeCmd(bp::tuple args, bp::dict) {
Command& command = bp::template extract<Command&>(args[0]);
if (bp::len(args) != int(command.valueTypes().size() + 1))
// TODO Put expected and given number of args
throw std::out_of_range("Wrong number of arguments");
std::vector<Value> values;
values.reserve(command.valueTypes().size());
for (int i = 1; i < bp::len(args); ++i)
values.push_back(convert::toValue(args[i], command.valueTypes()[i - 1]));
command.setParameterValues(values);
return convert::fromValue(command.execute());
}
} // namespace entity
} // namespace python
} // namespace dynamicgraph
"""
Copyright (C) 2010 CNRS
# Copyright (C) 2020 CNRS
#
# Author: Florent Lamiraux, Nicolas Mansard
Author: Florent Lamiraux, Nicolas Mansard
"""
import new
from enum import Enum
from __future__ import print_function
import signal_base
import wrap
from attrpath import setattrpath
if 'display' not in globals().keys():
def display(s):
print(s)
# --- FACTORY ------------------------------------------------------------------
# --- FACTORY ------------------------------------------------------------------
# --- FACTORY ------------------------------------------------------------------
class PyEntityFactoryClass(type):
"""
The class build dynamically a new class type, and return the reference
on the class-type object. The class type is not added to any context.
"""
def __new__(factory, className, bases=(), dict={}):
if len(bases) == 0:
# Initialize a basic Entity class
EntityClass = type.__new__(factory, className, (Entity, ), dict)
EntityClass.className = className
EntityClass.__init__ = Entity.initEntity
else:
# Initialize a heritated class
EntityClass = type.__new__(factory, className, bases, dict)
for c in bases:
if issubclass(c, Entity):
EntityClass.className = c.className
break
EntityClass.commandCreated = False
return EntityClass
def PyEntityFactory(className, context):
"""
Build a new class type by calling the factory, and add it
to the given context.
"""
EntityClass = PyEntityFactoryClass(className)
context[className] = EntityClass
return EntityClass
def updateEntityClasses(dictionary):
"""
For all c++entity types that are not in the pyentity class list
(entityClassNameList) run the factory and store the new type in the given
context (dictionary).
"""
cxx_entityList = wrap.factory_get_entity_class_list()
for e in filter(lambda x: x not in Entity.entityClassNameList, cxx_entityList):
# Store new class in dictionary with class name
PyEntityFactory(e, dictionary)
# Store class name in local list
Entity.entityClassNameList.append(e)
# --- ENTITY -------------------------------------------------------------------
# --- ENTITY -------------------------------------------------------------------
# --- ENTITY -------------------------------------------------------------------
class VerbosityLevel(Enum):
"""
Enum class for setVerbosityLevel
"""
VERBOSITY_ALL = 0
VERBOSITY_INFO_WARNING_ERROR = 1
VERBOSITY_WARNING_ERROR = 2
VERBOSITY_ERROR = 3
VERBOSITY_NONE = 4
class Entity(object):
"""
This class binds dynamicgraph::Entity C++ class
"""
obj = None
"""
Store list of entities created via python
"""
entities = dict()
def __init__(self, className, instanceName):
"""
Constructor: if not called by a child class, create and store a pointer
to a C++ Entity object.
"""
object.__setattr__(self, 'obj', wrap.create_entity(className, instanceName))
Entity.entities[instanceName] = self
@staticmethod
def initEntity(self, name):
"""
Common constructor of specialized Entity classes. This function is bound
by the factory to each new class derivated from the Entity class as the
constructor of the new class.
"""
Entity.__init__(self, self.className, name)
if not self.__class__.commandCreated:
self.boundClassCommands()
self.__class__.__doc__ = wrap.entity_get_docstring(self.obj)
self.__class__.commandCreated = True
@property
def name(self):
return wrap.entity_get_name(self.obj)
@property
def className(self):
return wrap.entity_get_class_name(self.obj)
def __str__(self):
return wrap.display_entity(self.obj)
def signal(self, name):
"""
Get a signal of the entity from signal name
"""
signalPt = wrap.entity_get_signal(self.obj, name)
return signal_base.SignalBase(name="", obj=signalPt)
def hasSignal(self, name):
"""
Indicates if a signal with the given name exists in the entity
"""
return wrap.entity_has_signal(self.obj, name)
def displaySignals(self):
"""
Print the list of signals into standard output: temporary.
"""
signals = self.signals()
if len(signals) == 0:
display("--- <" + self.name + "> has no signal")
else:
display("--- <" + self.name + "> signal list: ")
for s in signals[:-1]:
display(" |-- <" + str(s))
display(" `-- <" + str(signals[-1]))
def signals(self):
"""
Return the list of signals
"""
sl = wrap.entity_list_signals(self.obj)
return map(lambda pyObj: signal_base.SignalBase(obj=pyObj), sl)
def commands(self):
"""
Return the list of commands.
"""
return wrap.entity_list_commands(self.obj)
def globalHelp(self):
"""
Print a short description of each command.
"""
if self.__doc__:
print(self.__doc__)
print("List of commands:")
print("-----------------")
for cstr in self.commands():
ctitle = cstr + ':'
for i in range(len(cstr), 15):
ctitle += ' '
for docstr in wrap.entity_get_command_docstring(self.obj, cstr).split('\n'):
if (len(docstr) > 0) and (not docstr.isspace()):
display(ctitle + "\t" + docstr)
break
def help(self, comm=None):
"""
With no arg, print the global help. With arg the name of
a specific command, print the help associated to the command.
"""
if comm is None:
self.globalHelp()
else:
display(comm + ":\n" + wrap.entity_get_command_docstring(self.obj, comm))
def __getattr__(self, name):
try:
return self.signal(name)
except Exception:
try:
object.__getattr__(self, name)
except AttributeError:
raise AttributeError("'%s' entity has no attribute %s\n" % (self.name, name) +
' entity attributes are usually either\n' + ' - commands,\n' +
' - signals or,\n' + ' - user defined attributes')
def __setattr__(self, name, value):
if name in map(lambda s: s.getName().split(':')[-1], self.signals()):
raise NameError(name + " already designates a signal. "
"It is not advised to set a new attribute of the same name.")
object.__setattr__(self, name, value)
# --- COMMANDS BINDER -----------------------------------------------------
# List of all the entity classes from the c++ factory, that have been bound
# bind the py factory.
entityClassNameList = []
# This function dynamically create the function object that runs the command.
@staticmethod
def createCommandBind(name, docstring):
def commandBind(self, *arg):
return wrap.entity_execute_command(self.obj, name, arg)
commandBind.__doc__ = docstring
return commandBind
def boundClassCommands(self):
"""
This static function has to be called from a class heritating from Entity.
It should be called only once. It parses the list of commands obtained from
c++, and bind each of them to a python class method.
"""
# Get list of commands of the Entity object
commands = wrap.entity_list_commands(self.obj)
# for each command, add a method with the name of the command
for cmdstr in commands:
docstr = wrap.entity_get_command_docstring(self.obj, cmdstr)
cmdpy = Entity.createCommandBind(cmdstr, docstr)
setattrpath(self.__class__, cmdstr, cmdpy)
def boundNewCommand(self, cmdName):
"""
At construction, all existing commands are bound directly in the class.
This method enables to bound new commands dynamically. These new bounds
are not made with the class, but directly with the object instance.
"""
if (cmdName in self.__dict__) | (cmdName in self.__class__.__dict__):
print("Warning: command ", cmdName, " will overwrite an object attribute.")
docstring = wrap.entity_get_command_docstring(self.obj, cmdName)
cmd = Entity.createCommandBind(cmdName, docstring)
# Limitation (todo): does not handle for path attribute name (see setattrpath).
setattr(self, cmdName, new.instancemethod(cmd, self, self.__class__))
def boundAllNewCommands(self):
"""
For all commands that are not attribute of the object instance nor of the
class, a new attribute of the instance is created to bound the command.
"""
cmdList = wrap.entity_list_commands(self.obj)
cmdList = filter(lambda x: x not in self.__dict__, cmdList)
cmdList = filter(lambda x: x not in self.__class__.__dict__, cmdList)
for cmd in cmdList:
self.boundNewCommand(cmd)
def setLoggerVerbosityLevel(self, verbosity):
"""
Specify for the entity the verbosity level
"""
return wrap.entity_set_logger_verbosity(self.obj, verbosity)
def getLoggerVerbosityLevel(self):
"""
Returns the entity's verbosity level
"""
r = wrap.entity_get_logger_verbosity(self.obj)
if r == 0:
return VerbosityLevel.VERBOSITY_ALL
elif r == 1:
return VerbosityLevel.VERBOSITY_INFO_WARNING_ERROR
elif r == 2:
return VerbosityLevel.VERBOSITY_WARNING_ERROR
elif r == 3:
return VerbosityLevel.VERBOSITY_ERROR
return VerbosityLevel.VERBOSITY_NONE
def setTimeSample(self, timeSample):
"""
Specify for the entity the time at which call is counted.
"""
return wrap.entity_set_time_sample(self.obj, timeSample)
def getTimeSample(self):
"""
Returns for the entity the time at which call is counted.
"""
return wrap.entity_get_time_sample(self.obj)
def setStreamPrintPeriod(self, streamPrintPeriod):
"""
Specify for the entity the period at which debugging information is printed
"""
return wrap.entity_set_stream_print_period(self.obj, streamPrintPeriod)
def getStreamPrintPeriod(self):
"""
Returns for the entity the period at which debugging information is printed
"""
return wrap.entity_get_stream_print_period(self.obj)
# for backward compat
from .wrap import LoggerVerbosity as VerbosityLevel # noqa
from .wrap import Entity # noqa
// Copyright 2010, Florent Lamiraux, Thomas Moulard, LAAS-CNRS.
#include <Python.h>
#include <iostream>
#include <dynamic-graph/factory.h>
#include <iostream>
#include "dynamic-graph/python/dynamic-graph-py.hh"
using dynamicgraph::Entity;
using dynamicgraph::ExceptionAbstract;
......@@ -15,22 +17,10 @@ namespace factory {
/**
\brief Get name of entity
*/
PyObject* getEntityClassList(PyObject* /*self*/, PyObject* args) {
if (!PyArg_ParseTuple(args, "")) return NULL;
bp::tuple getEntityClassList() {
std::vector<std::string> classNames;
dynamicgraph::FactoryStorage::getInstance()->listEntities(classNames);
Py_ssize_t classNumber = classNames.size();
// Build a tuple object
PyObject* classTuple = PyTuple_New(classNumber);
for (Py_ssize_t iEntity = 0; iEntity < (Py_ssize_t)classNames.size(); ++iEntity) {
PyObject* className = Py_BuildValue("s", classNames[iEntity].c_str());
PyTuple_SetItem(classTuple, iEntity, className);
}
return Py_BuildValue("O", classTuple);
return to_py_tuple(classNames.begin(), classNames.end());
}
} // namespace factory
......
# The matlab class is define to produce a nice rendering of vector and matrix
# signals. The class builds at construction a string from the display
# of the matrix/vector, and stores the string internally. The string can be recovered
# using the str() member.
# The statics prec, space and fullPrec can be used to modify the display.
def pseudozero(prec):
"""
Return a string with '0...' and enough space to fill prec cars.
"""
res = '0...'
for i in range(2, prec):
res += ' '
return res
class matlab:
prec = 12
space = 2
fullPrec = 1e-5
def __init__(self, obj):
try:
return self.matlabFromMatrix(obj)
except Exception:
pass
try:
return self.matlabFromVector(obj)
except Exception:
pass
self.resstr = str(obj)
def __str__(self):
return self.resstr
def matlabFromMatrix(self, A):
fm = '%.' + str(self.prec) + 'f'
maxstr = 0
mstr = (())
for v in A:
lnstr = ()
for x in v:
if (abs(x) < self.fullPrec * self.fullPrec):
curr = '0'
else:
if (abs(x) < self.fullPrec):
curr = pseudozero(self.prec)
else:
curr = ' ' + (fm % x)
if (maxstr < len(curr)):
maxstr = len(curr)
lnstr += (curr, )
mstr += (lnstr, )
maxstr += self.space
resstr = '[...\n'
first = True
for v in mstr:
if first:
first = False
else:
resstr += ' ;\n'
firstC = True
for x in v:
if firstC:
firstC = False
else:
resstr += ','
for i in range(1, maxstr - len(x)):
resstr += ' '
resstr += x
resstr += ' ];'
self.resstr = resstr
def matlabFromVector(self, v):
fm = '%.' + str(self.prec) + 'f'
maxstr = 0
vstr = (())
for x in v:
if (abs(x) < self.fullPrec * self.fullPrec):
curr = '0'
else:
if (abs(x) < self.fullPrec):
curr = pseudozero(self.prec)
else:
curr = ' ' + (fm % x)
if (maxstr < len(curr)):
maxstr = len(curr)
vstr += (curr, )
maxstr += self.space
resstr = '[ '
first = True
for x in vstr:
if first:
first = False
else:
resstr += ','
for i in range(1, maxstr - len(x)):
resstr += ' '
resstr += x
resstr += ' ]\';'
self.resstr = resstr
// Copyright 2011, 2012, Florent Lamiraux, LAAS-CNRS.
#include <dynamic-graph/entity.h>
#include <dynamic-graph/pool.h>
#include <vector>
#include "dynamic-graph/python/dynamic-graph-py.hh"
namespace dynamicgraph {
namespace python {
namespace pool {
void writeGraph(const char* filename) {
PoolStorage::getInstance()->writeGraph(filename);
}
const std::map<std::string, Entity*>* getEntityMap() {
return &PoolStorage::getInstance()->getEntityMap();
}
/**
\brief Get list of entities
*/
bp::list getEntityList() {
std::vector<std::string> entityNames;
bp::list res;
const PoolStorage::Entities& listOfEntities =
PoolStorage::getInstance()->getEntityMap();
for (const auto& el : listOfEntities) res.append(el.second->getName());
return res;
}
} // namespace pool
} // namespace python
} // namespace dynamicgraph
#include "dynamic-graph/python/python-compat.hh"
// Get any PyObject and get its str() representation as an std::string
std::string obj_to_str(PyObject* o) {
std::string ret;
PyObject* os;
#if PY_MAJOR_VERSION >= 3
os = PyObject_Str(o);
assert(os != NULL);
assert(PyUnicode_Check(os));
ret = PyUnicode_AsUTF8(os);
#else
os = PyObject_Unicode(o);
assert(os != NULL);
assert(PyUnicode_Check(os));
PyObject* oss = PyUnicode_AsUTF8String(os);
assert(oss != NULL);
ret = PyString_AsString(oss);
Py_DECREF(oss);
#endif
Py_DECREF(os);
return ret;
}
......@@ -8,20 +8,21 @@
# entity -> same as print(entity)
# change the prompt to be '%'
from __future__ import print_function
# Changing prompt
import sys
from dynamic_graph.entity import Entity
from dynamic_graph.signal_base import SignalBase
from matlab import matlab
from .entity import Entity
from .signal_base import SignalBase
# Enables shortcut "name"
def sig_short_name(self):
return self.getName().split(':')[-1]
return self.getName().split(":")[-1]
setattr(SignalBase, 'name', property(sig_short_name))
setattr(SignalBase, "name", property(sig_short_name))
# Enables shortcuts "m"
......@@ -37,7 +38,7 @@ class PrettySignalPrint:
self.sig = sig
def __str__(self):
return self.sig.name + " = " + str(matlab(self.sig.value))
return self.sig.name + " = " + str(self.sig.value)
def __repr__(self):
return str(self)
......@@ -55,14 +56,12 @@ def sigMatPrint(sig):
return PrettySignalPrint(sig)
setattr(SignalBase, 'm', property(PrettySignalPrint))
# print('Pretty matlab print set')
setattr(SignalBase, "m", property(PrettySignalPrint))
# Enable the same as 'm', but directly on the signal object.
def sigRepr(self):
return self.name + ' = ' + str(matlab(self.value))
return self.name + " = " + str(self.value)
def sigCall(sig, iter):
......@@ -75,9 +74,9 @@ def sigTimeIncr(sig, iter):
print(sigRepr(sig))
setattr(SignalBase, '__repr__', sigRepr)
setattr(SignalBase, '__call__', sigCall)
setattr(SignalBase, '__add__', sigTimeIncr)
setattr(SignalBase, "__repr__", sigRepr)
setattr(SignalBase, "__call__", sigCall)
setattr(SignalBase, "__add__", sigTimeIncr)
# Enables shortcut "deps"
......@@ -98,12 +97,12 @@ class SignalDepPrint:
return self
setattr(SignalBase, 'deps', property(SignalDepPrint))
setattr(SignalBase, "deps", property(SignalDepPrint))
setattr(Entity, 'sigs', property(Entity.displaySignals))
setattr(Entity, '__repr__', Entity.__str__)
setattr(Entity, "sigs", property(Entity.displaySignals))
setattr(Entity, "__repr__", Entity.__str__)
sys.ps1 = '% '
sys.ps1 = "% "
# Enable function that can be call without()def optionalparentheses(f):
......@@ -117,7 +116,7 @@ def optionalparentheses(f):
if isinstance(res, str):
return res
else:
return ''
return ""
def __call__(self, *arg):
return self.functor(*arg)
......
// Copyright 2010, Florent Lamiraux, Thomas Moulard, LAAS-CNRS.
#include <dynamic-graph/linear-algebra.h>
#include <dynamic-graph/signal-base.h>
#include <dynamic-graph/signal-ptr.h>
#include <dynamic-graph/signal-time-dependent.h>
#include <dynamic-graph/signal.h>
#include <dynamic-graph/value.h>
#include <boost/python.hpp>
#include <iostream>
#include <sstream>
#include "dynamic-graph/python/dynamic-graph-py.hh"
#include "dynamic-graph/python/signal-wrapper.hh"
#include "dynamic-graph/python/signal.hh"
using dynamicgraph::SignalBase;
namespace bp = boost::python;
namespace dynamicgraph {
namespace python {
typedef int time_type;
typedef Eigen::AngleAxis<double> VectorUTheta;
typedef Eigen::Quaternion<double> Quaternion;
typedef Eigen::VectorXd Vector;
typedef Eigen::Vector3d Vector3;
typedef Eigen::Matrix<double, 7, 1> Vector7;
typedef Eigen::MatrixXd Matrix;
typedef Eigen::Matrix<double, 3, 3> MatrixRotation;
typedef Eigen::Matrix<double, 4, 4> Matrix4;
typedef Eigen::Transform<double, 3, Eigen::Affine> MatrixHomogeneous;
typedef Eigen::Matrix<double, 6, 6> MatrixTwist;
template <typename Time>
void exposeSignalBase(const char* name) {
typedef SignalBase<Time> S_t;
bp::class_<S_t, boost::noncopyable>(name, bp::no_init)
.add_property("time",
bp::make_function(
&S_t::getTime,
bp::return_value_policy<bp::copy_const_reference>()),
&S_t::setTime)
.add_property("name",
bp::make_function(
&S_t::getName,
bp::return_value_policy<bp::copy_const_reference>()))
.def("getName", &S_t::getName,
bp::return_value_policy<bp::copy_const_reference>())
.def(
"getClassName",
+[](const S_t& s) -> std::string {
std::string ret;
s.getClassName(ret);
return ret;
})
.def("plug", &S_t::plug, "Plug the signal to another signal")
.def("unplug", &S_t::unplug, "Unplug the signal")
.def("isPlugged", &S_t::isPlugged, "Whether the signal is plugged")
.def("getPlugged", &S_t::getPluged,
bp::return_value_policy<bp::reference_existing_object>(),
"To which signal the signal is plugged")
.def("recompute", &S_t::recompute, "Recompute the signal at given time")
.def(
"__str__",
+[](const S_t& s) -> std::string {
std::ostringstream oss;
s.display(oss);
return oss.str();
})
.def(
"displayDependencies",
+[](const S_t& s, int time) -> std::string {
std::ostringstream oss;
s.displayDependencies(oss, time);
return oss.str();
},
"Print the signal dependencies in a string");
}
template <>
auto exposeSignal<MatrixHomogeneous, time_type>(const std::string& name) {
typedef Signal<MatrixHomogeneous, time_type> S_t;
bp::class_<S_t, bp::bases<SignalBase<time_type> >, boost::noncopyable> obj(
name.c_str(), bp::init<std::string>());
obj.add_property(
"value",
+[](const S_t& signal) -> Matrix4 {
return signal.accessCopy().matrix();
},
+[](S_t& signal, const Matrix4& v) {
// TODO it isn't hard to support pinocchio::SE3 type here.
// However, this adds a dependency to pinocchio.
signal.setConstant(MatrixHomogeneous(v));
},
"the signal value.");
return obj;
}
void exposeSignals() {
exposeSignalBase<time_type>("SignalBase");
exposeSignalsOfType<bool, time_type>("Bool");
exposeSignalsOfType<int, time_type>("Int");
exposeSignalsOfType<double, time_type>("Double");
exposeSignalsOfType<Vector, time_type>("Vector");
exposeSignalsOfType<Vector3, time_type>("Vector3");
exposeSignalsOfType<Vector7, time_type>("Vector7");
exposeSignalsOfType<Matrix, time_type>("Matrix");
exposeSignalsOfType<MatrixRotation, time_type>("MatrixRotation");
exposeSignalsOfType<MatrixHomogeneous, time_type>("MatrixHomogeneous");
exposeSignalsOfType<MatrixTwist, time_type>("MatrixTwist");
exposeSignalsOfType<Quaternion, time_type>("Quaternion");
exposeSignalsOfType<VectorUTheta, time_type>("VectorUTheta");
}
namespace signalBase {
template <class T>
SignalWrapper<T, int>* createSignalWrapperTpl(const char* name, bp::object o,
std::string& error) {
typedef SignalWrapper<T, int> SignalWrapper_t;
if (!SignalWrapper_t::checkCallable(o, error)) {
return NULL;
}
SignalWrapper_t* obj = new SignalWrapper_t(name, o);
return obj;
}
PythonSignalContainer* getPythonSignalContainer() {
Entity* obj = entity::create("PythonSignalContainer", "python_signals");
return dynamic_cast<PythonSignalContainer*>(obj);
}
#define SIGNAL_WRAPPER_TYPE(IF, Enum, Type) \
IF(command::Value::typeName(command::Value::Enum).compare(type) == 0) { \
obj = createSignalWrapperTpl<Type>(name, object, error); \
}
/**
\brief Create an instance of SignalWrapper
*/
SignalBase<int>* createSignalWrapper(const char* name, const char* type,
bp::object object) {
PythonSignalContainer* psc = getPythonSignalContainer();
if (psc == NULL) return NULL;
SignalBase<int>* obj = NULL;
std::string error;
SIGNAL_WRAPPER_TYPE(if, BOOL, bool)
// SIGNAL_WRAPPER_TYPE(else if, UNSIGNED ,bool)
SIGNAL_WRAPPER_TYPE(else if, INT, int)
SIGNAL_WRAPPER_TYPE(else if, FLOAT, float)
SIGNAL_WRAPPER_TYPE(else if, DOUBLE, double)
// SIGNAL_WRAPPER_TYPE(else if, STRING ,bool)
SIGNAL_WRAPPER_TYPE(else if, VECTOR, Vector)
// SIGNAL_WRAPPER_TYPE(else if, MATRIX ,bool)
// SIGNAL_WRAPPER_TYPE(else if, MATRIX4D ,bool)
else {
error = "Type not understood";
}
if (obj == NULL) throw std::runtime_error(error);
// Register signal into the python signal container
psc->signalRegistration(*obj);
// Return the pointer
return obj;
}
} // namespace signalBase
} // namespace python
} // namespace dynamicgraph
// Copyright (c) 2018, Joseph Mirabel
// Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
#include "signal-wrapper.hh"
#include "dynamic-graph/python/signal-wrapper.hh"
#include <Python.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/command-bind.h>
#include <dynamic-graph/factory.h>
namespace dynamicgraph {
namespace python {
namespace signalWrapper {
void convert(PyObject* o, bool& v) { v = (o == Py_True); }
void convert(PyObject* o, int& v) { v = (int)PyInt_AS_LONG(o); }
void convert(PyObject* o, float& v) { v = (float)PyFloat_AS_DOUBLE(o); }
void convert(PyObject* o, double& v) { v = PyFloat_AS_DOUBLE(o); }
void convert(PyObject* o, Vector& v) {
v.resize(PyTuple_Size(o));
for (int i = 0; i < v.size(); ++i) convert(PyTuple_GetItem(o, i), v[i]);
}
} // namespace signalWrapper
PythonSignalContainer::PythonSignalContainer(const std::string& name) : Entity(name) {
std::string docstring;
docstring =
" \n"
" Remove a signal\n"
" \n"
" Input:\n"
" - name of the signal\n"
" \n";
addCommand("rmSignal", command::makeCommandVoid1(*this, &PythonSignalContainer::rmSignal, docstring));
}
void PythonSignalContainer::signalRegistration(const SignalArray<int>& signals) {
void PythonSignalContainer::signalRegistration(
const SignalArray<int>& signals) {
Entity::signalRegistration(signals);
}
void PythonSignalContainer::rmSignal(const std::string& name) { Entity::signalDeregistration(name); }
void PythonSignalContainer::rmSignal(const std::string& name) {
Entity::signalDeregistration(name);
}
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(PythonSignalContainer, "PythonSignalContainer");
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(PythonSignalContainer,
"PythonSignalContainer");
template <class T, class Time>
bool SignalWrapper<T, Time>::checkCallable(PyObject* c, std::string& error) {
if (PyCallable_Check(c) == 0) {
PyObject* str = PyObject_Str(c);
error = PyString_AsString(str);
bool SignalWrapper<T, Time>::checkCallable(pyobject c, std::string& error) {
if (PyCallable_Check(c.ptr()) == 0) {
error = boost::python::extract<std::string>(c.attr("__str__")());
error += " is not callable";
Py_DECREF(str);
return false;
}
return true;
......
"""
Copyright (C) 2010 CNRS
# Copyright (C) 2020 CNRS
#
# Author: Joseph Mirabel
Author: Florent Lamiraux
"""
from __future__ import print_function
# I kept what follows for backward compatibility but I think it should be
# removed
import re
import entity
import wrap
from .wrap import SignalBase # noqa
from .wrap import create_signal_wrapper as SignalWrapper # noqa
def stringToTuple(vector):
......@@ -14,17 +17,22 @@ def stringToTuple(vector):
Transform a string of format '[n](x_1,x_2,...,x_n)' into a tuple of numbers.
"""
# Find vector length
a = re.match(r'\[(\d+)\]', vector)
a = re.match(r"\[(\d+)\]", vector)
size = int(a.group(1))
# remove '[n]' prefix
vector = vector[len(a.group(0)):]
vector = vector[len(a.group(0)) :]
# remove '(' and ')' at beginning and end
vector = vector.lstrip('(').rstrip(')\n')
vector = vector.lstrip("(").rstrip(")\n")
# split string by ','
vector = vector.split(',')
vector = vector.split(",")
# check size
if len(vector) != size:
raise TypeError('displayed size ' + str(size) + ' of vector does not fit actual size: ' + str(len(vector)))
raise TypeError(
"displayed size "
+ str(size)
+ " of vector does not fit actual size: "
+ str(len(vector))
)
res = map(float, vector)
return tuple(res)
......@@ -34,10 +42,10 @@ def tupleToString(vector):
Transform a tuple of numbers into a string of format
'[n](x_1, x_2, ..., x_n)'
"""
string = '[%d](' % len(vector)
string = "[%d](" % len(vector)
for x in vector[:-1]:
string += '%f,' % x
string += '%f)' % vector[-1]
string += "%f," % x
string += "%f)" % vector[-1]
return string
......@@ -48,20 +56,30 @@ def stringToMatrix(string):
of tuple of numbers.
"""
# Find matrix size
a = re.search(r'\[(\d+),(\d+)]', string)
a = re.search(r"\[(\d+),(\d+)]", string)
nRows = int(a.group(1))
nCols = int(a.group(2))
# Remove '[n,m]' prefix
string = string[len(a.group(0)):]
rows = string.split('),(')
string = string[len(a.group(0)) :]
rows = string.split("),(")
if len(rows) != nRows:
raise TypeError('displayed nb rows ' + nRows + ' of matrix does not fit actual nb rows: ' + str(len(rows)))
raise TypeError(
"displayed nb rows "
+ nRows
+ " of matrix does not fit actual nb rows: "
+ str(len(rows))
)
m = []
for rstr in rows:
rstr = rstr.lstrip('(').rstrip(')\n')
r = map(float, rstr.split(','))
rstr = rstr.lstrip("(").rstrip(")\n")
r = map(float, rstr.split(","))
if len(r) != nCols:
raise TypeError('one row length ' + len(r) + ' of matrix does not fit displayed nb cols: ' + nCols)
raise TypeError(
"one row length "
+ len(r)
+ " of matrix does not fit displayed nb cols: "
+ nCols
)
m.append(tuple(r))
return tuple(m)
......@@ -73,19 +91,19 @@ def matrixToString(matrix):
"""
nRows = len(matrix)
if nRows == 0:
return '[0,0](())'
return "[0,0](())"
nCols = len(matrix[0])
string = '[%d,%d](' % (nRows, nCols)
string = "[%d,%d](" % (nRows, nCols)
for r in range(nRows):
string += '('
string += "("
for c in range(nCols):
string += str(float(matrix[r][c]))
if c != nCols - 1:
string += ','
string += ')'
string += ","
string += ")"
if r != nRows - 1:
string += ','
string += ')'
string += ","
string += ")"
return string
......@@ -99,18 +117,18 @@ def objectToString(obj):
- an integer,
- a boolean,
"""
if (hasattr(obj, "__iter__")):
if hasattr(obj, "__iter__"):
# matrix or vector
if len(obj) == 0:
return ""
else:
if (hasattr(obj[0], "__iter__")):
if hasattr(obj[0], "__iter__"):
# matrix
return matrixToString(obj)
else:
# vector
return tupleToString(obj)
elif isinstance(obj, entity.Entity):
elif hasattr(obj, "name"):
return obj.name
else:
return str(obj)
......@@ -148,136 +166,3 @@ def stringToObject(string):
return float(string)
except Exception:
return string
class SignalBase(object):
"""
This class binds dynamicgraph::SignalBase<int> C++ class
"""
obj = None
def __init__(self, name="", obj=None):
"""
Constructor: if not called by a child class, create and store a pointer
to a C++ SignalBase<int> object.
"""
if obj:
self.obj = obj
else:
raise RuntimeError("A pointer is required to create SignalBase object.")
if obj is None:
self.className = self.getClassName()
self.name = self.getName()
@property
def time(self):
"""
Get time of signal
"""
return wrap.signal_base_get_time(self.obj)
@time.setter
def time(self, val):
"""
Set Time of signal
Input:
- an integer
"""
return wrap.signal_base_set_time(self.obj, val)
@property
def value(self):
"""
Setter and getter for the value of a signal
Binds C++ SignalBase<int>::get() and set() methods. Values are passed
through string streams.
A string is interpreted as respectively:
* a matrix (tuple of tuple) if string fits '[n,m]((x_11,x_12,...,x_1m),...,(x_n1,x_n2,...,x_nm))' format where
n and m are integers, x_ij are floating point numbers,
* a tuple if string fits '[n](x_1, x_2, ..., x_n)' format,
* an integer,
* a floating point number.
If string fits none of the above formats, no conversion is performed.
For instance, is s binds a signal of type vector,
>>> s.value = (2.5, .1, 1e2)
will call SignalBase<int>::set("[3](2.5,0.1,100.0)") and
>>> s.value
(2.5, 0.1, 100.0)
"""
string = wrap.signal_base_get_value(self.obj)
return stringToObject(string)
@value.setter
def value(self, val):
"""
Set the signal as a constant signal with given value.
If the signal is plugged, it will be unplugged
"""
string = objectToString(val)
return wrap.signal_base_set_value(self.obj, string)
def getName(self):
"""
Get name of signal
"""
return wrap.signal_base_get_name(self.obj)
@property
def name(self):
"""
Get name of signal
"""
return wrap.signal_base_get_name(self.obj)
def getClassName(self):
"""
Get class name of signal
"""
return wrap.signal_base_get_class_name(self.obj)
def recompute(self, time):
"""
Force signal to recompute the value at given time.
"""
return wrap.signal_base_recompute(self.obj, time)
def unplug(self):
"""
Unplug a PTR signal.
"""
return wrap.signal_base_unplug(self.obj)
def isPlugged(self):
"""
Return whether a signal is plugged.
"""
return wrap.signal_base_isPlugged(self.obj)
def getPlugged(self):
"""
Return the plugged signal.
"""
return SignalBase(obj=wrap.signal_base_getPlugged(self.obj))
def __str__(self):
"""
Print signal in a string
"""
return wrap.signal_base_display(self.obj)
def displayDependencies(self, iter):
"""
Print signal dependencies in a string
"""
return (wrap.signal_base_display_dependencies(self.obj, iter))
class SignalWrapper(SignalBase):
def __init__(self, name, type, func):
super(SignalWrapper, self).__init__(name, wrap.create_signal_wrapper(name, type, func))
......@@ -8,8 +8,8 @@ def addTrace(robot, trace, entityName, signalName, autoRecompute=True):
"""
Add a signal to a tracer and recompute it automatically if necessary.
"""
signal = '{0}.{1}'.format(entityName, signalName)
filename = '{0}-{1}'.format(entityName, signalName)
signal = "{0}.{1}".format(entityName, signalName)
filename = "{0}-{1}".format(entityName, signalName).replace("/", "_")
trace.add(signal, filename)
if autoRecompute:
robot.device.after.addSignal(signal)
#include <dynamic-graph/tracer.h>
#include "dynamic-graph/python/module.hh"
BOOST_PYTHON_MODULE(wrap) {
using dynamicgraph::Tracer;
bp::import("dynamic_graph");
dynamicgraph::python::exposeEntity<Tracer>().def("addSignal",
&Tracer::addSignalToTrace);
}
#include <dynamic-graph/tracer-real-time.h>
#include "dynamic-graph/python/module.hh"
BOOST_PYTHON_MODULE(wrap) {
using dynamicgraph::Tracer;
using dynamicgraph::TracerRealTime;
bp::import("dynamic_graph.tracer");
dynamicgraph::python::exposeEntity<TracerRealTime, bp::bases<Tracer> >();
}
// Copyright 2010, Florent Lamiraux, Thomas Moulard, LAAS-CNRS.
#include <Python.h>
#include <iostream>
#include <dynamic-graph/entity.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/command.h>
#include <dynamic-graph/value.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/linear-algebra.h>
#include "convert-dg-to-py.hh"
#include "exception.hh"
// Ignore "dereferencing type-punned pointer will break strict-aliasing rules"
// warnings on gcc caused by Py_RETURN_TRUE and Py_RETURN_FALSE.
#if (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 2))
#pragma GCC diagnostic ignored "-Wstrict-aliasing"
#endif
using dynamicgraph::Entity;
using dynamicgraph::Matrix;
using dynamicgraph::SignalBase;
using dynamicgraph::Vector;
using dynamicgraph::command::Command;
using dynamicgraph::command::Value;
namespace dynamicgraph {
namespace python {
extern PyObject* dgpyError;
using namespace convert;
namespace entity {
/**
\brief Create an instance of Entity
*/
PyObject* create(PyObject* /*self*/, PyObject* args) {
char* className = NULL;
char* instanceName = NULL;
if (!PyArg_ParseTuple(args, "ss", &className, &instanceName)) return NULL;
Entity* obj = NULL;
/* Try to find if the corresponding object already exists. */
if (dynamicgraph::PoolStorage::getInstance()->existEntity(instanceName, obj)) {
if (obj->getClassName() != className) {
std::string msg("Found an object named " + std::string(instanceName) +
",\n"
"but this object is of type " +
std::string(obj->getClassName()) + " and not " + std::string(className));
PyErr_SetString(dgpyError, msg.c_str());
return NULL;
}
} else /* If not, create a new object. */
{
try {
obj = dynamicgraph::FactoryStorage::getInstance()->newEntity(std::string(className), std::string(instanceName));
}
CATCH_ALL_EXCEPTIONS();
}
// Return the pointer as a PyCObject
return PyCObject_FromVoidPtr((void*)obj, NULL);
}
/**
\brief Get name of entity
*/
PyObject* getName(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
void* pointer = NULL;
std::string name;
if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "function takes a PyCObject as argument");
return NULL;
}
pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
try {
name = entity->getName();
}
CATCH_ALL_EXCEPTIONS();
return Py_BuildValue("s", name.c_str());
}
/**
\brief Get class name of entity
*/
PyObject* getClassName(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
void* pointer = NULL;
std::string name;
if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "function takes a PyCObject as argument");
return NULL;
}
pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
try {
name = entity->getClassName();
}
CATCH_ALL_EXCEPTIONS();
return Py_BuildValue("s", name.c_str());
}
/**
\brief Check if the entity has a signal with the given name
*/
PyObject* hasSignal(PyObject* /*self*/, PyObject* args) {
char* name = NULL;
PyObject* object = NULL;
void* pointer = NULL;
if (!PyArg_ParseTuple(args, "Os", &object, &name)) Py_RETURN_FALSE;
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "function takes a PyCObject as argument");
Py_RETURN_FALSE;
}
pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
bool hasSignal = false;
try {
hasSignal = entity->hasSignal(std::string(name));
}
CATCH_ALL_EXCEPTIONS();
if (hasSignal)
Py_RETURN_TRUE;
else
Py_RETURN_FALSE;
}
/**
\brief Get a signal by name
*/
PyObject* getSignal(PyObject* /*self*/, PyObject* args) {
char* name = NULL;
PyObject* object = NULL;
void* pointer = NULL;
if (!PyArg_ParseTuple(args, "Os", &object, &name)) return NULL;
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "function takes a PyCObject as argument");
return NULL;
}
pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
SignalBase<int>* signal = NULL;
try {
signal = &(entity->getSignal(std::string(name)));
}
CATCH_ALL_EXCEPTIONS();
// Return the pointer to the signal without destructor since the signal
// is not owned by the calling object but by the Entity.
return PyCObject_FromVoidPtr((void*)signal, NULL);
}
PyObject* listSignals(PyObject* /*self*/, PyObject* args) {
void* pointer = NULL;
PyObject* object = NULL;
if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
if (!PyCObject_Check(object)) return NULL;
pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
try {
Entity::SignalMap signalMap = entity->getSignalMap();
// Create a tuple of same size as the command map
PyObject* result = PyTuple_New(signalMap.size());
unsigned int count = 0;
for (Entity::SignalMap::iterator it = signalMap.begin(); it != signalMap.end(); it++) {
SignalBase<int>* signal = it->second;
PyObject* pySignal = PyCObject_FromVoidPtr((void*)signal, NULL);
PyTuple_SET_ITEM(result, count, pySignal);
count++;
}
return result;
}
CATCH_ALL_EXCEPTIONS();
return NULL;
}
PyObject* executeCommand(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
PyObject* argTuple = NULL;
char* commandName = NULL;
void* pointer = NULL;
if (!PyArg_ParseTuple(args, "OsO", &object, &commandName, &argTuple)) {
return NULL;
}
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "first argument is not an object");
return NULL;
}
pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
// Retrieve the argument tuple
if (!PyTuple_Check(argTuple)) {
PyErr_SetString(PyExc_TypeError, "third argument is not a tuple");
return NULL;
}
Py_ssize_t size = PyTuple_Size(argTuple);
std::map<const std::string, Command*> commandMap = entity->getNewStyleCommandMap();
if (commandMap.count(std::string(commandName)) != 1) {
std::ostringstream oss;
oss << "'" << entity->getName() << "' entity has no command '" << commandName << "'.";
PyErr_SetString(PyExc_AttributeError, oss.str().c_str());
return NULL;
}
Command* command = commandMap[std::string(commandName)];
// Check that tuple size is equal to command number of arguments
const std::vector<Value::Type> typeVector = command->valueTypes();
if ((unsigned)size != typeVector.size()) {
std::stringstream ss;
ss << "command takes " << typeVector.size() << " parameters, " << size << " given.";
PyErr_SetString(dgpyError, ss.str().c_str());
return NULL;
}
std::vector<Value> valueVector;
for (Py_ssize_t iParam = 0; iParam < size; iParam++) {
PyObject* PyValue = PyTuple_GetItem(argTuple, iParam);
Value::Type valueType = typeVector[iParam];
try {
Value value = pythonToValue(PyValue, valueType);
valueVector.push_back(value);
} catch (const std::exception& exc) {
std::stringstream ss;
ss << "while parsing argument " << iParam + 1 << ": expecting " << exc.what() << ".";
PyErr_SetString(dgpyError, ss.str().c_str());
return NULL;
} catch (...) {
PyErr_SetString(dgpyError, "Unknown exception");
return NULL;
}
}
command->setParameterValues(valueVector);
try {
Value result = command->execute();
return valueToPython(result);
}
CATCH_ALL_EXCEPTIONS();
return NULL;
}
PyObject* listCommands(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
if (!PyArg_ParseTuple(args, "O", &object)) {
return NULL;
}
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "function takes a PyCObject as argument");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
typedef std::map<const std::string, command::Command*> CommandMap;
CommandMap map = entity->getNewStyleCommandMap();
Py_ssize_t nbCommands = (Py_ssize_t)map.size();
// Create a tuple of same size as the command map
PyObject* result = PyTuple_New(nbCommands);
unsigned int count = 0;
for (CommandMap::iterator it = map.begin(); it != map.end(); it++) {
std::string commandName = it->first;
PyObject* pyName = Py_BuildValue("s", commandName.c_str());
PyTuple_SET_ITEM(result, count, pyName);
count++;
}
return result;
}
PyObject* getCommandDocstring(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
char* commandName;
if (!PyArg_ParseTuple(args, "Os", &object, &commandName)) {
return NULL;
}
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(dgpyError, "first argument is not an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
typedef std::map<const std::string, command::Command*> commandMap_t;
typedef std::map<const std::string, command::Command*>::iterator iterator_t;
commandMap_t map = entity->getNewStyleCommandMap();
command::Command* command = NULL;
iterator_t it = map.find(commandName);
if (it == map.end()) {
std::ostringstream oss;
oss << "'" << entity->getName() << "' entity has no command '" << commandName << "'.";
PyErr_SetString(PyExc_AttributeError, oss.str().c_str());
return NULL;
}
command = it->second;
std::string docstring = command->getDocstring();
return Py_BuildValue("s", docstring.c_str());
}
PyObject* getDocString(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
if (!PyArg_ParseTuple(args, "O", &object)) {
return NULL;
}
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(dgpyError, "first argument is not an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
try {
return Py_BuildValue("s", entity->getDocString().c_str());
} catch (const std::exception& exc) {
PyErr_SetString(dgpyError, exc.what());
return NULL;
} catch (...) {
PyErr_SetString(dgpyError, "Unknown exception");
return NULL;
}
return NULL;
}
PyObject* display(PyObject* /*self*/, PyObject* args) {
/* Retrieve the entity instance. */
PyObject* object = NULL;
if (!PyArg_ParseTuple(args, "O", &object) || (!PyCObject_Check(object))) {
PyErr_SetString(dgpyError, "first argument is not an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
/* Run the display function. */
std::ostringstream oss;
entity->display(oss);
/* Return the resulting string. */
return Py_BuildValue("s", oss.str().c_str());
}
/**
\brief Set verbosity Level
*/
PyObject* setLoggerVerbosityLevel(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
PyObject* objectVerbosityLevel = NULL;
if (!PyArg_ParseTuple(args, "OO", &object, &objectVerbosityLevel)) return NULL;
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "First argument should be an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
// Retrieve object verbosity level
PyObject* valueOfVerbosityLevel = PyObject_GetAttrString(objectVerbosityLevel, "value");
long verbosityLevel = PyLong_AsLong(valueOfVerbosityLevel);
try {
switch (verbosityLevel) {
case 0:
entity->setLoggerVerbosityLevel(VERBOSITY_ALL);
break;
case 1:
entity->setLoggerVerbosityLevel(VERBOSITY_INFO_WARNING_ERROR);
break;
case 2:
entity->setLoggerVerbosityLevel(VERBOSITY_WARNING_ERROR);
break;
case 3:
entity->setLoggerVerbosityLevel(VERBOSITY_ERROR);
break;
case 4:
entity->setLoggerVerbosityLevel(VERBOSITY_NONE);
break;
default:
entity->setLoggerVerbosityLevel(VERBOSITY_NONE);
break;
}
} catch (const std::exception& exc) {
PyErr_SetString(dgpyError, exc.what());
return NULL;
} catch (const char* s) {
PyErr_SetString(dgpyError, s);
return NULL;
} catch (...) {
PyErr_SetString(dgpyError, "Unknown exception");
return NULL;
}
return Py_BuildValue("");
}
/**
\brief Get verbosity Level
*/
PyObject* getLoggerVerbosityLevel(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "first argument is not an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
LoggerVerbosity alv;
try {
alv = entity->getLoggerVerbosityLevel();
}
CATCH_ALL_EXCEPTIONS();
int ares = (int)alv;
return Py_BuildValue("i", ares);
}
/**
\brief Get stream print period
*/
PyObject* getStreamPrintPeriod(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "first argument is not an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
double r;
try {
r = entity->getStreamPrintPeriod();
}
CATCH_ALL_EXCEPTIONS();
return Py_BuildValue("d", r);
}
/**
\brief Set print period
*/
PyObject* setStreamPrintPeriod(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
double streamPrintPeriod = 0;
if (!PyArg_ParseTuple(args, "Od", &object, &streamPrintPeriod)) return NULL;
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "First argument should be an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
try {
entity->setStreamPrintPeriod(streamPrintPeriod);
} catch (const std::exception& exc) {
PyErr_SetString(dgpyError, exc.what());
return NULL;
} catch (const char* s) {
PyErr_SetString(dgpyError, s);
return NULL;
} catch (...) {
PyErr_SetString(dgpyError, "Unknown exception");
return NULL;
}
return Py_BuildValue("");
}
/**
\brief Get stream print period
*/
PyObject* getTimeSample(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "first argument is not an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
double r;
try {
r = entity->getTimeSample();
}
CATCH_ALL_EXCEPTIONS();
return Py_BuildValue("d", r);
}
/**
\brief Set time sample
*/
PyObject* setTimeSample(PyObject* /*self*/, PyObject* args) {
PyObject* object = NULL;
double timeSample;
if (!PyArg_ParseTuple(args, "Od", &object, &timeSample)) return NULL;
// Retrieve the entity instance
if (!PyCObject_Check(object)) {
PyErr_SetString(PyExc_TypeError, "First argument should be an object");
return NULL;
}
void* pointer = PyCObject_AsVoidPtr(object);
Entity* entity = (Entity*)pointer;
try {
entity->setTimeSample(timeSample);
} catch (const std::exception& exc) {
PyErr_SetString(dgpyError, exc.what());
return NULL;
} catch (const char* s) {
PyErr_SetString(dgpyError, s);
return NULL;
} catch (...) {
PyErr_SetString(dgpyError, "Unknown exception");
return NULL;
}
return Py_BuildValue("");
}
} // namespace entity
} // namespace python
} // namespace dynamicgraph
/*
* Copyright 2010,
* François Bleibel,
* Olivier Stasse,
*
* CNRS/AIST
*
*/
#include <dynamic-graph/python/exception-python.hh>
#include <dynamic-graph/debug.h>
#include <stdarg.h>
#include <cstdio>
namespace dynamicgraph {
namespace python {
/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
/* --------------------------------------------------------------------- */
const std::string ExceptionPython::EXCEPTION_NAME = "Python";
ExceptionPython::ExceptionPython(const ExceptionPython::ErrorCodeEnum& errcode, const std::string& msg)
: ExceptionAbstract(errcode, msg) {
dgDEBUGF(15, "Created with message <%s>.", msg.c_str());
dgDEBUG(1) << "Created with message <%s>." << msg << std::endl;
}
ExceptionPython::ExceptionPython(const ExceptionPython::ErrorCodeEnum& errcode, const std::string& msg,
const char* format, ...)
: ExceptionAbstract(errcode, msg) {
va_list args;
va_start(args, format);
const unsigned int SIZE = 256;
char buffer[SIZE];
vsnprintf(buffer, SIZE, format, args);
dgDEBUG(15) << "Created "
<< " with message <" << msg << "> and buffer <" << buffer << ">. " << std::endl;
message += buffer;
va_end(args);
dgDEBUG(1) << "Throw exception " << EXCEPTION_NAME << "[#" << errcode << "]: "
<< "<" << message << ">." << std::endl;
}
} // namespace python
} // namespace dynamicgraph
/*
* Local variables:
* c-basic-offset: 2
* End:
*/
// Copyright 2010, Florent Lamiraux, Thomas Moulard, LAAS-CNRS.
#ifndef DYNAMIC_GRAPH_PYTHON_EXCEPTION
#define DYNAMIC_GRAPH_PYTHON_EXCEPTION
/// \brief Catch all exceptions which may be sent when C++ code is
/// called.
#define CATCH_ALL_EXCEPTIONS() \
catch (const std::exception& exc) { \
PyErr_SetString(dgpyError, exc.what()); \
return NULL; \
} \
catch (const char* s) { \
PyErr_SetString(dgpyError, s); \
return NULL; \
} \
catch (...) { \
PyErr_SetString(dgpyError, "Unknown exception"); \
return NULL; \
} \
struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n
#endif //! DYNAMIC_GRAPH_PYTHON_EXCEPTION