joystick_mux.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015-2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 #include <sensor_msgs/Joy.h>
32 
34 
36 
38 {
39 private:
45  double timeout_;
49  int selected_;
50 
51  void cbJoy(const sensor_msgs::Joy::Ptr msg)
52  {
53  last_joy_msg_ = ros::Time::now();
54  if (msg->buttons[interrupt_button_])
55  {
56  selected_ = 1;
57  }
58  else
59  {
60  selected_ = 0;
61  }
62  };
64  {
65  if (selected_ == id)
66  {
67  if (!advertised_)
68  {
69  advertised_ = true;
72  {
73  ROS_ERROR(
74  "Use %s (%s%s) topic instead of %s (%s%s)",
75  nh_.resolveName("mux_output", false).c_str(),
77  "mux_output",
78  pnh_.resolveName("output", false).c_str(),
80  "output");
81  pub_topic_ = msg->advertise(pnh_, "output", 1, false);
82  }
83  else
84  {
85  pub_topic_ = msg->advertise(nh_, "mux_output", 1, false);
86  }
87  }
88  pub_topic_.publish(*msg);
89  }
90  };
91 
92 public:
94  : nh_("")
95  , pnh_("~")
96  {
98  sub_joy_ = nh_.subscribe("joy", 1, &JoystickMux::cbJoy, this);
99  sub_topics_[0] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
100  nh_, "mux_input0",
101  pnh_, "input0", 1, boost::bind(&JoystickMux::cbTopic, this, _1, 0));
102  sub_topics_[1] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
103  nh_, "mux_input1",
104  pnh_, "input1", 1, boost::bind(&JoystickMux::cbTopic, this, _1, 1));
105 
106  pnh_.param("interrupt_button", interrupt_button_, 5);
107  pnh_.param("timeout", timeout_, 0.5);
108  last_joy_msg_ = ros::Time::now();
109 
110  advertised_ = false;
111  selected_ = 0;
112  }
113  void spin()
114  {
115  ros::Rate wait(10);
116  while (ros::ok())
117  {
118  wait.sleep();
119  ros::spinOnce();
120  if (ros::Time::now() - last_joy_msg_ > ros::Duration(timeout_))
121  {
122  selected_ = 0;
123  }
124  }
125  }
126 };
127 
128 int main(int argc, char* argv[])
129 {
130  ros::init(argc, argv, "joystick_mux");
131 
132  JoystickMux jy;
133  jy.spin();
134 
135  return 0;
136 }
std::string getSimplifiedNamespace(ros::NodeHandle &nh)
ros::NodeHandle nh_
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber sub_topics_[2]
ros::Time last_joy_msg_
ros::NodeHandle pnh_
int interrupt_button_
void cbJoy(const sensor_msgs::Joy::Ptr msg)
ROSCPP_DECL bool ok()
bool sleep()
double timeout_
ros::Publisher pub_topic_
static Time now()
void cbTopic(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg, int id)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
int main(int argc, char *argv[])
ros::Subscriber sub_joy_


joystick_interrupt
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:53