Skip to content
Snippets Groups Projects
Commit 5ec15699 authored by Thomas Moulard's avatar Thomas Moulard
Browse files

Clean RosImport class.

parent 77b51e43
No related branches found
No related tags found
No related merge requests found
......@@ -26,19 +26,6 @@ namespace dynamicgraph
free (arg0);
nh_ = ros::NodeHandle ("dynamic_graph");
//ros::Publisher blob_pub = n.advertise<hueblob::Blob>("blob", 1000);
// ros::Rate loop_rate(10);
// while (ros::ok())
// {
// hueblob::Blob blob;
// blob_pub.publish(blob);
// ros::spinOnce();
// loop_rate.sleep();
// }
}
RosImport::~RosImport ()
......@@ -54,13 +41,17 @@ namespace dynamicgraph
std::istringstream& cmdArgs,
std::ostream& os)
{
std::string type;
std::string signal;
std::string topic;
if (cmdLine == "help")
{
os << "RosImport: "<< std::endl
<< " - add <SIGNAL> <TOPIC>" << std::endl;
<< " - add <TYPE> <SIGNAL> <TOPIC>" << std::endl
<< " - rm <SIGNAL>" << std::endl
<< " - clear" << std::endl
<< " - list" << std::endl;
Entity::commandLine (cmdLine, cmdArgs, os);
}
else if (cmdLine == "add")
......@@ -70,8 +61,8 @@ namespace dynamicgraph
}
else if (cmdLine == "rm")
{
cmdArgs >> signal >> topic;
rm (signal, topic);
cmdArgs >> signal;
rm (signal);
}
else if (cmdLine == "clear")
clear ();
......@@ -86,8 +77,9 @@ namespace dynamicgraph
return CLASS_NAME;
}
void RosImport::rm (const std::string& signal, const std::string& topic)
void RosImport::rm (const std::string& signal)
{
bindedSignal_.erase (signal);
}
void RosImport::list ()
......
......@@ -9,34 +9,14 @@
# include <ros/ros.h>
//FIXME: remove me.
#include <std_msgs/Float64.h>
template <typename SotType>
class SotToRos;
template <>
struct SotToRos<double>
{
typedef double sot_t;
typedef std_msgs::Float64 ros_t;
typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
typedef boost::function<sot_t& (sot_t&, int)> callback_t;
};
namespace dynamicgraph
{
template <typename SotType>
class SotToRos;
template <typename D, typename S>
void converter (D& dst, const S& src);
template <>
void converter (SotToRos<double>::ros_t& dst,
const SotToRos<double>::sot_t& src)
{
dst.data = src;
}
class RosImport : public dynamicgraph::Entity
{
public:
......@@ -56,57 +36,25 @@ namespace dynamicgraph
std::ostream& os);
virtual const std::string& getClassName();
virtual const std::string& getClassName ();
private:
void add (const std::string& signal, const std::string& topic);
void rm (const std::string& signal, const std::string& topic);
void rm (const std::string& signal);
void list ();
void clear ();
template <typename T>
T& sendData (boost::shared_ptr<ros::Publisher> publisher, T& data, int time)
{
typename SotToRos<T>::ros_t result;
converter (result, data);
publisher->publish (result);
return data;
}
T& sendData (boost::shared_ptr<ros::Publisher> publisher,
T& data, int time);
template <typename T>
void add (const std::string& signal, const std::string& topic)
{
typedef typename SotToRos<T>::sot_t sot_t;
typedef typename SotToRos<T>::ros_t ros_t;
typedef typename SotToRos<T>::signal_t signal_t;
typedef typename SotToRos<T>::callback_t callback_t;
// Initialize the bindedSignal object.
bindedSignal_t bindedSignal;
// Initialize the publisher.
bindedSignal.second =
boost::make_shared<ros::Publisher> (nh_.advertise<ros_t>(topic, 1));
// Initialize the signal.
boost::format signalName ("RosImport(%1%)::%2%");
signalName % name % signal;
callback_t signalCallback = boost::bind
(&RosImport::sendData<sot_t>, this, bindedSignal.second, _1, _2);
bindedSignal.first = boost::make_shared<signal_t>
(signalCallback, sotNOSIGNAL, signalName.str ());
signalRegistration (*bindedSignal.first);
bindedSignal_.push_back(bindedSignal);
}
void add (const std::string& signal, const std::string& topic);
ros::NodeHandle nh_;
std::vector<bindedSignal_t> bindedSignal_;
std::map<std::string, bindedSignal_t> bindedSignal_;
};
} // end of namespace dynamicgraph.
# include "ros_import.hxx"
#endif //! DYNAMIC_GRAPH_ROS_IMPORT_HH
#ifndef DYNAMIC_GRAPH_ROS_IMPORT_HXX
# define DYNAMIC_GRAPH_ROS_IMPORT_HXX
# include <std_msgs/Float64.h>
namespace dynamicgraph
{
template <>
struct SotToRos<double>
{
typedef double sot_t;
typedef std_msgs::Float64 ros_t;
typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
typedef boost::function<sot_t& (sot_t&, int)> callback_t;
};
template <>
void converter (SotToRos<double>::ros_t& dst,
const SotToRos<double>::sot_t& src)
{
dst.data = src;
}
template <typename T>
T&
RosImport::sendData (boost::shared_ptr<ros::Publisher> publisher,
T& data, int time)
{
typename SotToRos<T>::ros_t result;
converter (result, data);
publisher->publish (result);
return data;
}
template <typename T>
void RosImport::add (const std::string& signal, const std::string& topic)
{
typedef typename SotToRos<T>::sot_t sot_t;
typedef typename SotToRos<T>::ros_t ros_t;
typedef typename SotToRos<T>::signal_t signal_t;
typedef typename SotToRos<T>::callback_t callback_t;
// Initialize the bindedSignal object.
bindedSignal_t bindedSignal;
// Initialize the publisher.
bindedSignal.second =
boost::make_shared<ros::Publisher> (nh_.advertise<ros_t>(topic, 1));
// Initialize the signal.
boost::format signalName ("RosImport(%1%)::%2%");
signalName % name % signal;
callback_t signalCallback = boost::bind
(&RosImport::sendData<sot_t>, this, bindedSignal.second, _1, _2);
bindedSignal.first = boost::make_shared<signal_t>
(signalCallback, sotNOSIGNAL, signalName.str ());
signalRegistration (*bindedSignal.first);
bindedSignal_[signal] = bindedSignal;
}
} // end of namespace dynamicgraph.
#endif //! DYNAMIC_GRAPH_ROS_IMPORT_HXX
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment