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
  • gsaurel/dynamic_graph_bridge
  • stack-of-tasks/dynamic_graph_bridge
2 results
Show changes
Showing
with 1139 additions and 1285 deletions
#include <dynamic-graph/python/module.hh>
#include "ros_subscribe.hh"
namespace dg = dynamicgraph;
BOOST_PYTHON_MODULE(wrap) {
bp::import("dynamic_graph");
dg::python::exposeEntity<dg::RosSubscribe, bp::bases<dg::Entity>,
dg::python::AddCommands>()
.def("clear", &dg::RosSubscribe::clear,
"Remove all signals reading data from a ROS topic")
.def("rm", &dg::RosSubscribe::rm,
"Remove a signal reading data from a ROS topic",
bp::args("signal_name"))
.def("list", &dg::RosSubscribe::list,
"List signals reading data from a ROS topic");
}
#include <boost/assign.hpp> #include "ros_subscribe.hh"
#include <boost/bind.hpp>
#include <boost/format.hpp>
#include <boost/function.hpp>
#include <boost/make_shared.hpp>
#include <dynamic-graph/factory.h>
#include <ros/ros.h> #include <ros/ros.h>
#include <std_msgs/Float64.h> #include <std_msgs/Float64.h>
#include <std_msgs/UInt32.h> #include <std_msgs/UInt32.h>
#include <dynamic-graph/factory.h> #include <boost/assign.hpp>
#include <boost/bind.hpp>
#include <boost/format.hpp>
#include <boost/function.hpp>
#include <boost/make_shared.hpp>
#include "dynamic_graph_bridge/ros_init.hh" #include "dynamic_graph_bridge/ros_init.hh"
#include "ros_subscribe.hh"
namespace dynamicgraph namespace dynamicgraph {
{ DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(RosSubscribe, "RosSubscribe");
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(RosSubscribe, "RosSubscribe");
namespace command {
namespace command namespace rosSubscribe {
{ Add::Add(RosSubscribe& entity, const std::string& docstring)
namespace rosSubscribe : Command(
{ entity,
Clear::Clear boost::assign::list_of(Value::STRING)(Value::STRING)(Value::STRING),
(RosSubscribe& entity, const std::string& docstring) docstring) {}
: Command
(entity, Value Add::doExecute() {
std::vector<Value::Type> (), RosSubscribe& entity = static_cast<RosSubscribe&>(owner());
docstring) std::vector<Value> values = getParameterValues();
{}
const std::string& type = values[0].value();
Value Clear::doExecute () const std::string& signal = values[1].value();
{ const std::string& topic = values[2].value();
RosSubscribe& entity =
static_cast<RosSubscribe&> (owner ()); if (type == "double")
entity.add<double>(signal, topic);
entity.clear (); else if (type == "unsigned")
return Value (); entity.add<unsigned int>(signal, topic);
} else if (type == "matrix")
entity.add<dg::Matrix>(signal, topic);
List::List else if (type == "vector")
(RosSubscribe& entity, const std::string& docstring) entity.add<dg::Vector>(signal, topic);
: Command else if (type == "vector3")
(entity, entity.add<specific::Vector3>(signal, topic);
std::vector<Value::Type> (), else if (type == "vector3Stamped")
docstring) entity.add<std::pair<specific::Vector3, dg::Vector> >(signal, topic);
{} else if (type == "matrixHomo")
entity.add<sot::MatrixHomogeneous>(signal, topic);
Value List::doExecute () else if (type == "matrixHomoStamped")
{ entity.add<std::pair<sot::MatrixHomogeneous, dg::Vector> >(signal, topic);
RosSubscribe& entity = else if (type == "twist")
static_cast<RosSubscribe&> (owner ()); entity.add<specific::Twist>(signal, topic);
return Value (entity.list ()); else if (type == "twistStamped")
} entity.add<std::pair<specific::Twist, dg::Vector> >(signal, topic);
else if (type == "string")
Add::Add entity.add<std::string>(signal, topic);
(RosSubscribe& entity, const std::string& docstring) else
: Command throw std::runtime_error("bad type");
(entity, return Value();
boost::assign::list_of }
(Value::STRING) (Value::STRING) (Value::STRING), } // namespace rosSubscribe
docstring) } // end of namespace command.
{}
const std::string RosSubscribe::docstring_(
Value Add::doExecute () "Subscribe to a ROS topics and convert it into a dynamic-graph signals.\n"
{ "\n"
RosSubscribe& entity = " Use command \"add\" to subscribe to a new signal.\n");
static_cast<RosSubscribe&> (owner ());
std::vector<Value> values = getParameterValues (); RosSubscribe::RosSubscribe(const std::string& n)
: dynamicgraph::Entity(n), nh_(rosInit(true)), bindedSignal_() {
const std::string& type = values[0].value (); std::string docstring =
const std::string& signal = values[1].value ();
const std::string& topic = values[2].value ();
if (type == "double")
entity.add<double> (signal, topic);
else if (type == "unsigned")
entity.add<unsigned int> (signal, topic);
else if (type == "matrix")
entity.add<dg::Matrix> (signal, topic);
else if (type == "vector")
entity.add<dg::Vector> (signal, topic);
else if (type == "vector3")
entity.add<specific::Vector3> (signal, topic);
else if (type == "vector3Stamped")
entity.add<std::pair<specific::Vector3, dg::Vector> > (signal, topic);
else if (type == "matrixHomo")
entity.add<sot::MatrixHomogeneous> (signal, topic);
else if (type == "matrixHomoStamped")
entity.add<std::pair<sot::MatrixHomogeneous, dg::Vector> >
(signal, topic);
else if (type == "twist")
entity.add<specific::Twist> (signal, topic);
else if (type == "twistStamped")
entity.add<std::pair<specific::Twist, dg::Vector> >
(signal, topic);
else
throw std::runtime_error("bad type");
return Value ();
}
Rm::Rm
(RosSubscribe& entity, const std::string& docstring)
: Command
(entity,
boost::assign::list_of (Value::STRING),
docstring)
{}
Value Rm::doExecute ()
{
RosSubscribe& entity =
static_cast<RosSubscribe&> (owner ());
std::vector<Value> values = getParameterValues ();
const std::string& signal = values[0].value ();
entity.rm (signal);
return Value ();
}
} // end of errorEstimator.
} // end of namespace command.
const std::string RosSubscribe::docstring_
("Subscribe to a ROS topics and convert it into a dynamic-graph signals.\n"
"\n"
" Use command \"add\" to subscribe to a new signal.\n");
RosSubscribe::RosSubscribe (const std::string& n)
: dynamicgraph::Entity(n),
nh_ (rosInit (true)),
bindedSignal_ ()
{
std::string docstring =
"\n" "\n"
" Add a signal reading data from a ROS topic\n" " Add a signal reading data from a ROS topic\n"
"\n" "\n"
" Input:\n" " Input:\n"
" - type: string among ['double', 'matrix', 'vector', 'vector3',\n" " - type: string among ['double', 'matrix', 'vector', 'vector3',\n"
" 'vector3Stamped', 'matrixHomo', 'matrixHomoStamped',\n" " 'vector3Stamped', 'matrixHomo', "
"'matrixHomoStamped',\n"
" 'twist', 'twistStamped'],\n" " 'twist', 'twistStamped'],\n"
" - signal: the signal name in dynamic-graph,\n" " - signal: the signal name in dynamic-graph,\n"
" - topic: the topic name in ROS.\n" " - topic: the topic name in ROS.\n"
"\n"; "\n";
addCommand ("add", addCommand("add", new command::rosSubscribe::Add(*this, docstring));
new command::rosSubscribe::Add }
(*this, docstring));
docstring =
"\n"
" Remove a signal reading data from a ROS topic\n"
"\n"
" Input:\n"
" - name of the signal to remove (see method list for the list of signals).\n"
"\n";
addCommand ("rm",
new command::rosSubscribe::Rm
(*this, docstring));
docstring =
"\n"
" Remove all signals reading data from a ROS topic\n"
"\n"
" No input:\n"
"\n";
addCommand ("clear",
new command::rosSubscribe::Clear
(*this, docstring));
docstring =
"\n"
" List signals reading data from a ROS topic\n"
"\n"
" No input:\n"
"\n";
addCommand ("list",
new command::rosSubscribe::List
(*this, docstring));
}
RosSubscribe::~RosSubscribe () RosSubscribe::~RosSubscribe() {}
{}
void RosSubscribe::display (std::ostream& os) const void RosSubscribe::display(std::ostream& os) const {
{ os << CLASS_NAME << std::endl;
os << CLASS_NAME << std::endl; }
}
void RosSubscribe::rm (const std::string& signal) void RosSubscribe::rm(const std::string& signal) {
{ std::string signalTs = signal + "Timestamp";
std::string signalTs = signal+"Timestamp";
signalDeregistration(signal); signalDeregistration(signal);
bindedSignal_.erase (signal); bindedSignal_.erase(signal);
if(bindedSignal_.find(signalTs) != bindedSignal_.end()) if (bindedSignal_.find(signalTs) != bindedSignal_.end()) {
{ signalDeregistration(signalTs);
signalDeregistration(signalTs); bindedSignal_.erase(signalTs);
bindedSignal_.erase(signalTs);
}
} }
}
std::string RosSubscribe::list ()
{ std::vector<std::string> RosSubscribe::list() {
std::string result("["); std::vector<std::string> result(bindedSignal_.size());
for (std::map<std::string, bindedSignal_t>::const_iterator it = std::transform(bindedSignal_.begin(), bindedSignal_.end(), result.begin(),
bindedSignal_.begin (); it != bindedSignal_.end (); it++) { [](const auto& pair) { return pair.first; });
result += "'" + it->first + "',"; return result;
} }
result += "]";
return result; void RosSubscribe::clear() {
std::map<std::string, bindedSignal_t>::iterator it = bindedSignal_.begin();
for (; it != bindedSignal_.end();) {
rm(it->first);
it = bindedSignal_.begin();
} }
}
void RosSubscribe::clear () std::string RosSubscribe::getDocString() const { return docstring_; }
{ } // end of namespace dynamicgraph.
std::map<std::string, bindedSignal_t>::iterator it = bindedSignal_.begin();
for(; it!= bindedSignal_.end(); )
{
rm(it->first);
it = bindedSignal_.begin();
}
}
std::string RosSubscribe::getDocString () const
{
return docstring_;
}
} // end of namespace dynamicgraph.
#ifndef DYNAMIC_GRAPH_ROS_SUBSCRIBE_HH #ifndef DYNAMIC_GRAPH_ROS_SUBSCRIBE_HH
# define DYNAMIC_GRAPH_ROS_SUBSCRIBE_HH #define DYNAMIC_GRAPH_ROS_SUBSCRIBE_HH
# include <map> #include <dynamic-graph/command.h>
#include <dynamic-graph/entity.h>
# include <boost/shared_ptr.hpp> #include <dynamic-graph/signal-ptr.h>
#include <dynamic-graph/signal-time-dependent.h>
# include <dynamic-graph/entity.h> #include <ros/ros.h>
# include <dynamic-graph/signal-time-dependent.h>
# include <dynamic-graph/signal-ptr.h> #include <boost/shared_ptr.hpp>
# include <dynamic-graph/command.h> #include <map>
# include <sot/core/matrix-geometry.hh> #include <sot/core/matrix-geometry.hh>
# include <ros/ros.h> #include "converter.hh"
#include "sot_to_ros.hh"
# include "converter.hh"
# include "sot_to_ros.hh" namespace dynamicgraph {
class RosSubscribe;
namespace dynamicgraph
{ namespace command {
class RosSubscribe; namespace rosSubscribe {
using ::dynamicgraph::command::Command;
namespace command using ::dynamicgraph::command::Value;
{
namespace rosSubscribe #define ROS_SUBSCRIBE_MAKE_COMMAND(CMD) \
{ class CMD : public Command { \
using ::dynamicgraph::command::Command; public: \
using ::dynamicgraph::command::Value; CMD(RosSubscribe& entity, const std::string& docstring); \
virtual Value doExecute(); \
# define ROS_SUBSCRIBE_MAKE_COMMAND(CMD) \ }
class CMD : public Command \
{ \ ROS_SUBSCRIBE_MAKE_COMMAND(Add);
public: \
CMD (RosSubscribe& entity, \
const std::string& docstring); \
virtual Value doExecute (); \
}
ROS_SUBSCRIBE_MAKE_COMMAND(Add);
ROS_SUBSCRIBE_MAKE_COMMAND(Clear);
ROS_SUBSCRIBE_MAKE_COMMAND(List);
ROS_SUBSCRIBE_MAKE_COMMAND(Rm);
#undef ROS_SUBSCRIBE_MAKE_COMMAND #undef ROS_SUBSCRIBE_MAKE_COMMAND
} // end of namespace errorEstimator. } // namespace rosSubscribe
} // end of namespace command. } // end of namespace command.
namespace internal {
template <typename T>
struct Add;
} // namespace internal
namespace internal /// \brief Publish ROS information in the dynamic-graph.
{ class RosSubscribe : public dynamicgraph::Entity {
template <typename T> DYNAMIC_GRAPH_ENTITY_DECL();
struct Add; typedef boost::posix_time::ptime ptime;
} // end of internal namespace.
/// \brief Publish ROS information in the dynamic-graph. public:
class RosSubscribe : public dynamicgraph::Entity typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
{ boost::shared_ptr<ros::Subscriber> >
DYNAMIC_GRAPH_ENTITY_DECL();
typedef boost::posix_time::ptime ptime;
public:
typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
boost::shared_ptr<ros::Subscriber> >
bindedSignal_t; bindedSignal_t;
RosSubscribe (const std::string& n); RosSubscribe(const std::string& n);
virtual ~RosSubscribe (); virtual ~RosSubscribe();
virtual std::string getDocString () const; virtual std::string getDocString() const;
void display (std::ostream& os) const; void display(std::ostream& os) const;
void add (const std::string& signal, const std::string& topic); void add(const std::string& signal, const std::string& topic);
void rm (const std::string& signal); void rm(const std::string& signal);
std::string list (); std::vector<std::string> list();
void clear (); void clear();
template <typename T> template <typename T>
void add (const std::string& signal, const std::string& topic); void add(const std::string& signal, const std::string& topic);
std::map<std::string, bindedSignal_t>& std::map<std::string, bindedSignal_t>& bindedSignal() {
bindedSignal () return bindedSignal_;
{ }
return bindedSignal_;
} ros::NodeHandle& nh() { return nh_; }
ros::NodeHandle& nh () template <typename R, typename S>
{ void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal,
return nh_; const R& data);
}
template <typename R>
template <typename R, typename S> void callbackTimestamp(
void callback boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal, const R& data);
const R& data);
template <typename T>
template <typename R> friend class internal::Add;
void callbackTimestamp
(boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal, private:
const R& data); static const std::string docstring_;
ros::NodeHandle& nh_;
template <typename T> std::map<std::string, bindedSignal_t> bindedSignal_;
friend class internal::Add; };
private: } // end of namespace dynamicgraph.
static const std::string docstring_;
ros::NodeHandle& nh_; #include "ros_subscribe.hxx"
std::map<std::string, bindedSignal_t> bindedSignal_; #endif //! DYNAMIC_GRAPH_ROS_SUBSCRIBE_HH
};
} // end of namespace dynamicgraph.
# include "ros_subscribe.hxx"
#endif //! DYNAMIC_GRAPH_ROS_SUBSCRIBE_HH
This diff is collapsed.
#include <dynamic-graph/python/module.hh>
#include "ros_tf_listener.hh"
namespace dg = dynamicgraph;
BOOST_PYTHON_MODULE(wrap) {
bp::import("dynamic_graph");
dg::python::exposeEntity<dg::RosTfListener, bp::bases<dg::Entity>,
dg::python::AddCommands>()
.def("add", &dg::RosTfListener::add,
"Add a signal containing the transform between two frames.",
bp::args("to_frame_name", "from_frame_name", "out_signal_name"))
.def("setMaximumDelay", &dg::RosTfListener::setMaximumDelay,
"Set the maximum time delay of the transform obtained from tf.",
bp::args("signal_name", "delay_seconds"));
}
This diff is collapsed.
This diff is collapsed.
#include "ros_time.hh"
typedef boost::mpl::vector<dynamicgraph::RosTime> entities_t;
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
#include "sot_to_ros.hh" #include "sot_to_ros.hh"
namespace dynamicgraph namespace dynamicgraph {
{
const char* SotToRos<double>::signalTypeName = "Double"; const char* SotToRos<bool>::signalTypeName = "bool";
const char* SotToRos<unsigned int>::signalTypeName = "Unsigned"; const char* SotToRos<double>::signalTypeName = "Double";
const char* SotToRos<Matrix>::signalTypeName = "Matrix"; const char* SotToRos<int>::signalTypeName = "int";
const char* SotToRos<Vector>::signalTypeName = "Vector"; const char* SotToRos<std::string>::signalTypeName = "string";
const char* SotToRos<specific::Vector3>::signalTypeName = "Vector3"; const char* SotToRos<unsigned int>::signalTypeName = "Unsigned";
const char* SotToRos<sot::MatrixHomogeneous>::signalTypeName = "MatrixHomo"; const char* SotToRos<Matrix>::signalTypeName = "Matrix";
const char* SotToRos<specific::Twist>::signalTypeName = "Twist"; const char* SotToRos<Vector>::signalTypeName = "Vector";
const char* SotToRos const char* SotToRos<specific::Vector3>::signalTypeName = "Vector3";
<std::pair<specific::Vector3, Vector> >::signalTypeName const char* SotToRos<sot::MatrixHomogeneous>::signalTypeName = "MatrixHomo";
= "Vector3Stamped"; const char* SotToRos<specific::Twist>::signalTypeName = "Twist";
const char* SotToRos const char* SotToRos<std::pair<specific::Vector3, Vector> >::signalTypeName =
<std::pair<sot::MatrixHomogeneous, Vector> >::signalTypeName "Vector3Stamped";
= "MatrixHomo"; const char*
const char* SotToRos SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::signalTypeName =
<std::pair<specific::Twist, Vector> >::signalTypeName "MatrixHomo";
= "Twist"; const char* SotToRos<std::pair<specific::Twist, Vector> >::signalTypeName =
"Twist";
} // end of namespace dynamicgraph. } // end of namespace dynamicgraph.
This diff is collapsed.
string input
---
string result
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
root ALL=(ALL) ALL
docker ALL=(ALL) NOPASSWD: ALL
Defaults env_reset
Defaults secure_path="/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin"