joy_listener.cpp
Go to the documentation of this file.
1 #include <string>
2 
4 #include <ros/init.h>
5 #include <ros/names.h>
6 #include <ros/node_handle.h>
7 #include <ros/subscriber.h>
8 #include <sensor_msgs/Joy.h>
9 
10 #include <boost/regex.hpp>
11 
12 // params
14 boost::regex start_regex, stop_regex;
15 bool verbose;
16 
17 // memo
19 
20 // callback
21 void onJoyRecieved(const sensor_msgs::JoyConstPtr &joy) {
22  // handle the start button
23  const bool start_is_pressed(joy->buttons.size() > start_button_id &&
24  joy->buttons[start_button_id] > 0);
25  if (!start_was_pressed && start_is_pressed) {
27  }
28  start_was_pressed = start_is_pressed;
29 
30  // handle the stop button
31  const bool stop_is_pressed(joy->buttons.size() > stop_button_id &&
32  joy->buttons[stop_button_id] > 0);
33  if (!stop_was_pressed && stop_is_pressed) {
35  }
36  stop_was_pressed = stop_is_pressed;
37 }
38 
39 int main(int argc, char *argv[]) {
40  ros::init(argc, argv, "joy_listener");
41 
42  // load params
43  ros::NodeHandle nh, pnh("~");
44  start_button_id = pnh.param("start_button", 12 /* PS4's R3 button */);
45  stop_button_id = pnh.param("stop_button", 11 /* PS4's L3 button */);
46  start_regex =
47  pnh.param< std::string >("start_regex", ros::names::append(nh.getNamespace(), "start"));
48  stop_regex =
49  pnh.param< std::string >("stop_regex", ros::names::append(nh.getNamespace(), "stop"));
50  verbose = pnh.param("verbose", true);
51 
52  // init memos
53  start_was_pressed = false;
54  stop_was_pressed = false;
55 
56  // start subscribing
57  const ros::Subscriber sub(nh.subscribe("joy", 1, onJoyRecieved));
58 
59  ros::spin();
60 
61  return 0;
62 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int stop_button_id
void onJoyRecieved(const sensor_msgs::JoyConstPtr &joy)
static std::size_t call(const boost::regex &expression, const bool verbose=true)
Definition: call.hpp:20
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool verbose
const std::string & getNamespace() const
bool stop_was_pressed
ROSCPP_DECL void spin()
int start_button_id
int main(int argc, char *argv[])
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
bool start_was_pressed
boost::regex start_regex
boost::regex stop_regex


remote_rosbag_record
Author(s):
autogenerated on Wed Jan 27 2021 03:18:31