Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ros/ros.h>
00031 #include <sensor_msgs/Joy.h>
00032
00033 #include <topic_tools/shape_shifter.h>
00034
00035 #include <neonavigation_common/compatibility.h>
00036
00037 class JoystickMux
00038 {
00039 private:
00040 ros::NodeHandle nh_;
00041 ros::NodeHandle pnh_;
00042 ros::Subscriber sub_topics_[2];
00043 ros::Subscriber sub_joy_;
00044 ros::Publisher pub_topic_;
00045 double timeout_;
00046 int interrupt_button_;
00047 ros::Time last_joy_msg_;
00048 bool advertised_;
00049 int selected_;
00050
00051 void cbJoy(const sensor_msgs::Joy::Ptr msg)
00052 {
00053 last_joy_msg_ = ros::Time::now();
00054 if (msg->buttons[interrupt_button_])
00055 {
00056 selected_ = 1;
00057 }
00058 else
00059 {
00060 selected_ = 0;
00061 }
00062 };
00063 void cbTopic(const boost::shared_ptr<topic_tools::ShapeShifter const>& msg, int id)
00064 {
00065 if (selected_ == id)
00066 {
00067 if (!advertised_)
00068 {
00069 advertised_ = true;
00070 if (neonavigation_common::compat::getCompat() !=
00071 neonavigation_common::compat::current_level)
00072 {
00073 ROS_ERROR(
00074 "Use %s (%s%s) topic instead of %s (%s%s)",
00075 nh_.resolveName("mux_output", false).c_str(),
00076 neonavigation_common::compat::getSimplifiedNamespace(nh_).c_str(),
00077 "mux_output",
00078 pnh_.resolveName("output", false).c_str(),
00079 neonavigation_common::compat::getSimplifiedNamespace(pnh_).c_str(),
00080 "output");
00081 pub_topic_ = msg->advertise(pnh_, "output", 1, false);
00082 }
00083 else
00084 {
00085 pub_topic_ = msg->advertise(nh_, "mux_output", 1, false);
00086 }
00087 }
00088 pub_topic_.publish(*msg);
00089 }
00090 };
00091
00092 public:
00093 JoystickMux()
00094 : nh_("")
00095 , pnh_("~")
00096 {
00097 neonavigation_common::compat::checkCompatMode();
00098 sub_joy_ = nh_.subscribe("joy", 1, &JoystickMux::cbJoy, this);
00099 sub_topics_[0] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
00100 nh_, "mux_input0",
00101 pnh_, "input0", 1, boost::bind(&JoystickMux::cbTopic, this, _1, 0));
00102 sub_topics_[1] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
00103 nh_, "mux_input1",
00104 pnh_, "input1", 1, boost::bind(&JoystickMux::cbTopic, this, _1, 1));
00105
00106 pnh_.param("interrupt_button", interrupt_button_, 5);
00107 pnh_.param("timeout", timeout_, 0.5);
00108 last_joy_msg_ = ros::Time::now();
00109
00110 advertised_ = false;
00111 selected_ = 0;
00112 }
00113 void spin()
00114 {
00115 ros::Rate wait(10);
00116 while (ros::ok())
00117 {
00118 wait.sleep();
00119 ros::spinOnce();
00120 if (ros::Time::now() - last_joy_msg_ > ros::Duration(timeout_))
00121 {
00122 selected_ = 0;
00123 }
00124 }
00125 }
00126 };
00127
00128 int main(int argc, char* argv[])
00129 {
00130 ros::init(argc, argv, "joystick_mux");
00131
00132 JoystickMux jy;
00133 jy.spin();
00134
00135 return 0;
00136 }