remote_joy.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <sensor_msgs/Joy.h>
3 #include <std_srvs/Trigger.h>
4 #include <nav2d_operator/cmd.h>
6 
7 /******************************************************
8 Buttons:
9  0: A
10  1: B
11  2: X
12  3: Y
13  4: LB
14  5: RB
15  6: BACK
16  7: START
17  8: Logitech*
18  9: Left Stick
19 10: Right Stick
20 
21  ******************************************************/
22 
24 {
25 public:
26  Teleoperator();
27 
28 private:
29  void joyCB(const sensor_msgs::Joy::ConstPtr& msg);
30 
38 
46 
48 };
49 
51 {
52  // Button and Axis configuration
53  mAxisVelocity = 4;
54  mAxisDirection = 0;
55 
56  mButtonDriveMode = 5;
59  mButtonGetMap = 3;
60  mButtonStop = 1;
61 
62  mCommandPublisher = mNode.advertise<nav2d_operator::cmd>("cmd", 1);
63  mJoySubscriber = mNode.subscribe<sensor_msgs::Joy>("joy", 10, &Teleoperator::joyCB, this);
64  mStopClient = mNode.serviceClient<std_srvs::Trigger>(NAV_STOP_SERVICE);
65  mPauseClient = mNode.serviceClient<std_srvs::Trigger>(NAV_PAUSE_SERVICE);
68 
69  mButtonPressed = false;
70 }
71 
72 void Teleoperator::joyCB(const sensor_msgs::Joy::ConstPtr& msg)
73 {
74  // Ignore Button-Release events
75  if(mButtonPressed)
76  {
77  mButtonPressed = false;
78  }else
79  {
80  nav2d_operator::cmd cmd;
81  cmd.Turn = msg->axes[mAxisDirection] * -1.0;
82  cmd.Velocity = msg->axes[mAxisVelocity];
83  cmd.Mode = 0;
84  if(msg->buttons[mButtonDriveMode]) cmd.Mode = 1;
86  }
87 
88  if(msg->buttons[mButtonStop])
89  {
90  std_srvs::Trigger srv;
91  if(!mStopClient.call(srv))
92  {
93  ROS_ERROR("Failed to send STOP_COMMAND to Navigator.");
94  }
95  return;
96  }
97 
98  if(msg->buttons[mButtonPauseNavigator])
99  {
100  std_srvs::Trigger srv;
101  if(!mPauseClient.call(srv))
102  {
103  ROS_ERROR("Failed to send PAUSE_COMMAND to Navigator.");
104  }
105  return;
106  }
107 
108  if(msg->buttons[mButtonGetMap])
109  {
110  std_srvs::Trigger srv;
111  if(!mGetMapClient.call(srv))
112  {
113  ROS_ERROR("Failed to send GETMAP_COMMAND to GetMap-Client.");
114  }
115  mButtonPressed = true;
116  return;
117  }
118 
119  if(msg->buttons[mButtonStartExploration])
120  {
121  std_srvs::Trigger srv;
122  if(!mExploreClient.call(srv))
123  {
124  ROS_ERROR("Failed to send EXPLORE_COMMAND to Explore-Client.");
125  }
126  mButtonPressed = true;
127  return;
128  }
129 }
130 
131 int main(int argc, char** argv)
132 {
133  ros::init(argc, argv, "teleoperator");
134  Teleoperator tele_op;
135 
136  ros::spin();
137 }
ros::Subscriber mJoySubscriber
Definition: remote_joy.cpp:33
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int mButtonPauseNavigator
Definition: remote_joy.cpp:42
#define NAV_PAUSE_SERVICE
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())
string cmd
#define NAV_STOP_SERVICE
ros::Publisher mCommandPublisher
Definition: remote_joy.cpp:32
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void joyCB(const sensor_msgs::Joy::ConstPtr &msg)
Definition: remote_joy.cpp:72
#define NAV_EXPLORE_SERVICE
ROSCPP_DECL void spin(Spinner &spinner)
bool mButtonPressed
Definition: remote_joy.cpp:47
int mButtonStartExploration
Definition: remote_joy.cpp:43
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceClient mPauseClient
Definition: remote_joy.cpp:35
ros::ServiceClient mExploreClient
Definition: remote_joy.cpp:36
int main(int argc, char **argv)
Definition: remote_joy.cpp:131
ros::ServiceClient mGetMapClient
Definition: remote_joy.cpp:37
ros::ServiceClient mStopClient
Definition: remote_joy.cpp:34
#define NAV_GETMAP_SERVICE
int mAxisDirection
Definition: remote_joy.cpp:40
ros::NodeHandle mNode
Definition: remote_joy.cpp:31
#define ROS_ERROR(...)
int mButtonDriveMode
Definition: remote_joy.cpp:41


nav2d_remote
Author(s): Sebastian Kasperski
autogenerated on Thu Jun 6 2019 19:20:51