Go to the documentation of this file.00001
00009
00010
00011
00012
00013 #include <fstream>
00014 #include <std_msgs/String.h>
00015 #include <pluginlib/class_list_macros.h>
00016
00017 #include "yocs_cmd_vel_mux/cmd_vel_mux_nodelet.hpp"
00018 #include "yocs_cmd_vel_mux/exceptions.hpp"
00019
00020
00021
00022
00023
00024 namespace yocs_cmd_vel_mux {
00025
00026
00027
00028
00029
00030 void CmdVelMuxNodelet::cmdVelCallback(const geometry_msgs::Twist::ConstPtr& msg, unsigned int idx)
00031 {
00032
00033 cmd_vel_sub[idx].timer.stop();
00034 cmd_vel_sub[idx].timer.start();
00035
00036 cmd_vel_sub[idx].active = true;
00037
00038
00039
00040 if ((cmd_vel_sub.allowed == VACANT) ||
00041 (cmd_vel_sub.allowed == idx) ||
00042 (cmd_vel_sub[idx].priority > cmd_vel_sub[cmd_vel_sub.allowed].priority))
00043 {
00044 if (cmd_vel_sub.allowed != idx)
00045 {
00046 cmd_vel_sub.allowed = idx;
00047
00048
00049 std_msgs::StringPtr acv_msg(new std_msgs::String);
00050 acv_msg->data = cmd_vel_sub[idx].name;
00051 active_subscriber.publish(acv_msg);
00052 }
00053
00054 mux_cmd_vel_pub.publish(msg);
00055 }
00056 }
00057
00058 void CmdVelMuxNodelet::timerCallback(const ros::TimerEvent& event, unsigned int idx)
00059 {
00060 if (cmd_vel_sub.allowed == idx)
00061 {
00062
00063 cmd_vel_sub.allowed = VACANT;
00064
00065
00066 std_msgs::StringPtr acv_msg(new std_msgs::String);
00067 acv_msg->data = "idle";
00068 active_subscriber.publish(acv_msg);
00069 }
00070
00071 cmd_vel_sub[idx].active = false;
00072 }
00073
00074 void CmdVelMuxNodelet::onInit()
00075 {
00076 ros::NodeHandle &nh = this->getPrivateNodeHandle();
00077
00078
00079
00080
00081 dynamic_reconfigure_cb = boost::bind(&CmdVelMuxNodelet::reloadConfiguration, this, _1, _2);
00082 dynamic_reconfigure_server = new dynamic_reconfigure::Server<yocs_cmd_vel_mux::reloadConfig>(nh);
00083 dynamic_reconfigure_server->setCallback(dynamic_reconfigure_cb);
00084
00085 active_subscriber = nh.advertise <std_msgs::String> ("active", 1, true);
00086
00087
00088 std_msgs::StringPtr active_msg(new std_msgs::String);
00089 active_msg->data = "idle";
00090 active_subscriber.publish(active_msg);
00091
00092
00093 NODELET_DEBUG("CmdVelMux : successfully initialised");
00094 }
00095
00096 void CmdVelMuxNodelet::reloadConfiguration(yocs_cmd_vel_mux::reloadConfig &config, uint32_t unused_level)
00097 {
00098 std::string yaml_cfg_file;
00099 ros::NodeHandle &nh = this->getPrivateNodeHandle();
00100 if( config.yaml_cfg_file == "" )
00101 {
00102
00103 nh.getParam("yaml_cfg_file", yaml_cfg_file);
00104 }
00105 else
00106 {
00107 yaml_cfg_file = config.yaml_cfg_file;
00108 }
00109
00110
00111
00112
00113 std::ifstream ifs(yaml_cfg_file.c_str(), std::ifstream::in);
00114 if (ifs.good() == false)
00115 {
00116 NODELET_ERROR_STREAM("CmdVelMux : configuration file not found [" << yaml_cfg_file << "]");
00117 return;
00118 }
00119
00120 YAML::Node doc;
00121 #ifdef HAVE_NEW_YAMLCPP
00122 doc = YAML::Load(ifs);
00123 #else
00124 YAML::Parser parser(ifs);
00125 parser.GetNextDocument(doc);
00126 #endif
00127
00128
00129
00130
00131 std::string output_name("output");
00132 #ifdef HAVE_NEW_YAMLCPP
00133 if ( doc["publisher"] ) {
00134 doc["publisher"] >> output_name;
00135 }
00136 #else
00137 const YAML::Node *node = doc.FindValue("publisher");
00138 if ( node != NULL ) {
00139 *node >> output_name;
00140 }
00141 #endif
00142 mux_cmd_vel_pub = nh.advertise <geometry_msgs::Twist> (output_name, 10);
00143
00144
00145
00146
00147 try {
00148 cmd_vel_sub.configure(doc["subscribers"]);
00149 }
00150 catch(EmptyCfgException& e) {
00151 NODELET_WARN("CmdVelMux : yaml configured zero subscribers, check yaml content.");
00152 }
00153 catch(YamlException& e) {
00154 NODELET_ERROR_STREAM("CmdVelMux : yaml parsing problem [" << std::string(e.what()) + "]");
00155 }
00156
00157
00158 for (unsigned int i = 0; i < cmd_vel_sub.size(); i++)
00159 {
00160 cmd_vel_sub[i].subs =
00161 nh.subscribe<geometry_msgs::Twist>(cmd_vel_sub[i].topic, 10, CmdVelFunctor(i, this));
00162
00163
00164 cmd_vel_sub[i].timer =
00165 nh.createTimer(ros::Duration(cmd_vel_sub[i].timeout), TimerFunctor(i, this), true, false);
00166
00167 NODELET_DEBUG("CmdVelMux : subscribed to '%s' on topic '%s'. pr: %d, to: %.2f",
00168 cmd_vel_sub[i].name.c_str(), cmd_vel_sub[i].topic.c_str(),
00169 cmd_vel_sub[i].priority, cmd_vel_sub[i].timeout);
00170 }
00171
00172 NODELET_INFO_STREAM("CmdVelMux : (re)configured [" << yaml_cfg_file << "]");
00173 ifs.close();
00174 }
00175
00176 }
00177
00178 PLUGINLIB_EXPORT_CLASS(yocs_cmd_vel_mux::CmdVelMuxNodelet, nodelet::Nodelet);