00001 #ifndef H_CANOPEN_ROS_CHAIN
00002 #define H_CANOPEN_ROS_CHAIN
00003
00004 #include <canopen_master/canopen.h>
00005 #include <canopen_master/can_layer.h>
00006 #include <canopen_chain_node/GetObject.h>
00007 #include <canopen_chain_node/SetObject.h>
00008 #include <socketcan_interface/string.h>
00009 #include <ros/ros.h>
00010 #include <std_srvs/Trigger.h>
00011 #include <diagnostic_updater/diagnostic_updater.h>
00012 #include <boost/filesystem/path.hpp>
00013 #include <boost/weak_ptr.hpp>
00014 #include <boost/scoped_ptr.hpp>
00015 #include <pluginlib/class_loader.h>
00016
00017 namespace canopen{
00018
00019 class PublishFunc{
00020 public:
00021 typedef boost::function<void()> func_type;
00022
00023 static func_type create(ros::NodeHandle &nh, const std::string &name, boost::shared_ptr<canopen::Node> node, const std::string &key, bool force);
00024 private:
00025 template <typename Tpub, typename Tobj, bool forced> static void publish(ros::Publisher &pub, ObjectStorage::Entry<Tobj> &entry){
00026 Tpub msg;
00027 msg.data = (const typename Tpub::_data_type &)(forced? entry.get() : entry.get_cached());
00028 pub.publish(msg);
00029 }
00030 template<typename Tpub, typename Tobj> static func_type create(ros::NodeHandle &nh, const std::string &name, ObjectStorage::Entry<Tobj> entry, bool force){
00031 if(!entry.valid()) return 0;
00032 ros::Publisher pub = nh.advertise<Tpub>(name, 1);
00033 if(force){
00034 return boost::bind(PublishFunc::publish<Tpub, Tobj, true>, pub, entry);
00035 }else{
00036 return boost::bind(PublishFunc::publish<Tpub, Tobj, false>, pub, entry);
00037 }
00038 }
00039 };
00040
00041 class MergedXmlRpcStruct : public XmlRpc::XmlRpcValue{
00042 MergedXmlRpcStruct(const XmlRpc::XmlRpcValue& a) :XmlRpc::XmlRpcValue(a){ assertStruct(); }
00043 public:
00044 MergedXmlRpcStruct(){ assertStruct(); }
00045 MergedXmlRpcStruct(const XmlRpc::XmlRpcValue& a, const MergedXmlRpcStruct &b, bool recursive= true) :XmlRpc::XmlRpcValue(a){
00046 assertStruct();
00047
00048 for(ValueStruct::const_iterator it = b._value.asStruct->begin(); it != b._value.asStruct->end(); ++it){
00049 std::pair<XmlRpc::XmlRpcValue::iterator,bool> res = _value.asStruct->insert(*it);
00050
00051 if(recursive && !res.second && res.first->second.getType() == XmlRpc::XmlRpcValue::TypeStruct && it->second.getType() == XmlRpc::XmlRpcValue::TypeStruct){
00052 res.first->second = MergedXmlRpcStruct(res.first->second, it->second);
00053 }
00054 }
00055
00056
00057 }
00058 };
00059
00060 class Logger: public DiagGroup<canopen::Layer>{
00061 const boost::shared_ptr<canopen::Node> node_;
00062
00063 std::vector<boost::function< void (diagnostic_updater::DiagnosticStatusWrapper &)> > entries_;
00064
00065 static void log_entry(diagnostic_updater::DiagnosticStatusWrapper &stat, uint8_t level, const std::string &name, boost::function<std::string()> getter){
00066 if(stat.level >= level){
00067 try{
00068 stat.add(name, getter());
00069 }catch(...){
00070 stat.add(name, "<ERROR>");
00071 }
00072 }
00073 }
00074
00075 public:
00076 Logger(boost::shared_ptr<canopen::Node> node): node_(node) { add(node_); }
00077
00078 bool add(uint8_t level, const std::string &key, bool forced){
00079 try{
00080 ObjectDict::Key k(key);
00081 const boost::shared_ptr<const ObjectDict::Entry> entry = node_->getStorage()->dict_->get(k);
00082 std::string name = entry->desc.empty() ? key : entry->desc;
00083 entries_.push_back(boost::bind(log_entry, _1, level, name, node_->getStorage()->getStringReader(k, !forced)));
00084 return true;
00085 }
00086 catch(std::exception& e){
00087 ROS_ERROR_STREAM(boost::diagnostic_information(e));
00088 return false;
00089 }
00090 }
00091
00092 template<typename T> void add(const boost::shared_ptr<T> &n){
00093 DiagGroup::add(boost::static_pointer_cast<canopen::Layer>(n));
00094 }
00095
00096 virtual void log(diagnostic_updater::DiagnosticStatusWrapper &stat){
00097 if(node_->getState() == canopen::Node::Unknown){
00098 stat.summary(stat.WARN,"Not initailized");
00099 }else{
00100 LayerReport r;
00101 diag(r);
00102 if(r.bounded<LayerStatus::Unbounded>()){
00103 stat.summary(r.get(), r.reason());
00104 for(std::vector<std::pair<std::string, std::string> >::const_iterator it = r.values().begin(); it != r.values().end(); ++it){
00105 stat.add(it->first, it->second);
00106 }
00107 for(size_t i=0; i < entries_.size(); ++i) entries_[i](stat);
00108 }
00109 }
00110 }
00111 virtual ~Logger() {}
00112 };
00113
00114 class GuardedClassLoaderList {
00115 static std::vector< boost::shared_ptr<pluginlib::ClassLoaderBase> >& guarded_loaders(){
00116 static std::vector< boost::shared_ptr<pluginlib::ClassLoaderBase> > loaders;
00117 return loaders;
00118 }
00119 public:
00120 static void addLoader(boost::shared_ptr<pluginlib::ClassLoaderBase> b){
00121 guarded_loaders().push_back(b);
00122 }
00123 ~GuardedClassLoaderList(){
00124 guarded_loaders().clear();
00125 }
00126 };
00127
00128 template<typename T> class GuardedClassLoader {
00129 typedef pluginlib::ClassLoader<T> Loader;
00130 boost::shared_ptr<Loader> loader_;
00131 public:
00132 GuardedClassLoader(const std::string& package, const std::string& allocator_base_class)
00133 : loader_(new Loader(package, allocator_base_class)) {
00134 GuardedClassLoaderList::addLoader(loader_);
00135 }
00136 boost::shared_ptr<T> createInstance(const std::string& lookup_name){
00137 return loader_->createInstance(lookup_name);
00138 }
00139 };
00140
00141 template<typename T> class ClassAllocator : public GuardedClassLoader<typename T::Allocator> {
00142 public:
00143 ClassAllocator (const std::string& package, const std::string& allocator_base_class) : GuardedClassLoader<typename T::Allocator>(package, allocator_base_class) {}
00144 template<typename T1> boost::shared_ptr<T> allocateInstance(const std::string& lookup_name, const T1 & t1){
00145 return this->createInstance(lookup_name)->allocate(t1);
00146 }
00147 template<typename T1, typename T2> boost::shared_ptr<T> allocateInstance(const std::string& lookup_name, const T1 & t1, const T2 & t2){
00148 return this->createInstance(lookup_name)->allocate(t1, t2);
00149 }
00150 template<typename T1, typename T2, typename T3> boost::shared_ptr<T> allocateInstance(const std::string& lookup_name, const T1 & t1, const T2 & t2, const T3 & t3){
00151 return this->createInstance(lookup_name)->allocate(t1, t2, t3);
00152 }
00153 };
00154 class RosChain : GuardedClassLoaderList, public canopen::LayerStack {
00155 GuardedClassLoader<can::DriverInterface> driver_loader_;
00156 ClassAllocator<canopen::Master> master_allocator_;
00157 protected:
00158 boost::shared_ptr<can::DriverInterface> interface_;
00159 boost::shared_ptr<Master> master_;
00160 boost::shared_ptr<canopen::LayerGroupNoDiag<canopen::Node> > nodes_;
00161 boost::shared_ptr<canopen::LayerGroupNoDiag<canopen::EMCYHandler> > emcy_handlers_;
00162 std::map<std::string, boost::shared_ptr<canopen::Node> > nodes_lookup_;
00163 boost::shared_ptr<canopen::SyncLayer> sync_;
00164 std::vector<boost::shared_ptr<Logger > > loggers_;
00165 std::vector<PublishFunc::func_type> publishers_;
00166
00167 can::StateInterface::StateListener::Ptr state_listener_;
00168
00169 boost::scoped_ptr<boost::thread> thread_;
00170
00171 ros::NodeHandle nh_;
00172 ros::NodeHandle nh_priv_;
00173
00174 diagnostic_updater::Updater diag_updater_;
00175 ros::Timer diag_timer_;
00176
00177 boost::mutex mutex_;
00178 ros::ServiceServer srv_init_;
00179 ros::ServiceServer srv_recover_;
00180 ros::ServiceServer srv_halt_;
00181 ros::ServiceServer srv_shutdown_;
00182 ros::ServiceServer srv_get_object_;
00183 ros::ServiceServer srv_set_object_;
00184
00185 time_duration update_duration_;
00186
00187 struct HeartbeatSender{
00188 can::Frame frame;
00189 boost::shared_ptr<can::DriverInterface> interface;
00190 bool send(){
00191 return interface && interface->send(frame);
00192 }
00193 } hb_sender_;
00194 Timer heartbeat_timer_;
00195
00196 boost::atomic<bool> running_;
00197 boost::mutex diag_mutex_;
00198
00199 bool reset_errors_before_recover_;
00200
00201 void logState(const can::State &s);
00202 void run();
00203 virtual bool handle_init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
00204 virtual bool handle_recover(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
00205 virtual void handleWrite(LayerStatus &status, const LayerState ¤t_state);
00206 virtual void handleShutdown(LayerStatus &status);
00207 virtual bool handle_shutdown(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
00208 virtual bool handle_halt(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
00209
00210 bool handle_get_object(canopen_chain_node::GetObject::Request &req, canopen_chain_node::GetObject::Response &res);
00211 bool handle_set_object(canopen_chain_node::SetObject::Request &req, canopen_chain_node::SetObject::Response &res);
00212
00213 bool setup_bus();
00214 bool setup_sync();
00215 bool setup_heartbeat();
00216 bool setup_nodes();
00217 virtual bool nodeAdded(XmlRpc::XmlRpcValue ¶ms, const boost::shared_ptr<canopen::Node> &node, const boost::shared_ptr<Logger> &logger);
00218 void report_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat);
00219 virtual bool setup_chain();
00220 public:
00221 RosChain(const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv);
00222 bool setup();
00223 virtual ~RosChain();
00224 };
00225
00226 }
00227
00228 #endif
00229