joystick_mux.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015-2020, 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:
46  double timeout_;
50  int selected_;
51 
52  void cbJoy(const sensor_msgs::Joy::Ptr msg)
53  {
54  if (static_cast<size_t>(interrupt_button_) >= msg->buttons.size())
55  {
56  ROS_ERROR(
57  "Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
58  msg->buttons.size(), interrupt_button_);
59  return;
60  }
61 
62  last_joy_msg_ = ros::Time::now();
63  if (msg->buttons[interrupt_button_])
64  {
65  selected_ = 1;
66  }
67  else
68  {
69  selected_ = 0;
70  }
71  };
73  {
74  if (selected_ == id)
75  {
76  if (!advertised_)
77  {
78  advertised_ = true;
81  {
82  ROS_ERROR(
83  "Use %s (%s%s) topic instead of %s (%s%s)",
84  nh_.resolveName("mux_output", false).c_str(),
86  "mux_output",
87  pnh_.resolveName("output", false).c_str(),
89  "output");
90  pub_topic_ = msg->advertise(pnh_, "output", 1, false);
91  }
92  else
93  {
94  pub_topic_ = msg->advertise(nh_, "mux_output", 1, false);
95  }
96  }
97  pub_topic_.publish(*msg);
98  }
99  };
100  void cbTimer(const ros::TimerEvent& e)
101  {
102  if (ros::Time::now() - last_joy_msg_ > ros::Duration(timeout_))
103  {
104  selected_ = 0;
105  }
106  }
107 
108 public:
110  : nh_("")
111  , pnh_("~")
112  {
114  sub_joy_ = nh_.subscribe("joy", 1, &JoystickMux::cbJoy, this);
115  sub_topics_[0] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
116  nh_, "mux_input0",
117  pnh_, "input0", 1, boost::bind(&JoystickMux::cbTopic, this, _1, 0));
118  sub_topics_[1] = neonavigation_common::compat::subscribe<topic_tools::ShapeShifter>(
119  nh_, "mux_input1",
120  pnh_, "input1", 1, boost::bind(&JoystickMux::cbTopic, this, _1, 1));
121 
122  pnh_.param("interrupt_button", interrupt_button_, 5);
123  pnh_.param("timeout", timeout_, 0.5);
124  last_joy_msg_ = ros::Time::now();
125 
126  timer_ = nh_.createTimer(ros::Duration(0.1), &JoystickMux::cbTimer, this);
127 
128  advertised_ = false;
129  selected_ = 0;
130  }
131 };
132 
133 int main(int argc, char* argv[])
134 {
135  ros::init(argc, argv, "joystick_mux");
136 
137  JoystickMux jy;
138  ros::spin();
139 
140  return 0;
141 }
std::string getSimplifiedNamespace(ros::NodeHandle &nh)
ros::NodeHandle nh_
void cbTimer(const ros::TimerEvent &e)
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 void spin()
double timeout_
ros::Publisher pub_topic_
static Time now()
ros::Timer timer_
void cbTopic(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg, int id)
#define ROS_ERROR(...)
int main(int argc, char *argv[])
ros::Subscriber sub_joy_


joystick_interrupt
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:31