JoystickDemo.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 New Eagle
5  * Copyright (c) 2015-2018, Dataspeed Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Dataspeed Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include "JoystickDemo.h"
37 
38 namespace joystick_demo
39 {
40 
42 {
43  joy_.axes.resize(AXIS_COUNT, 0);
44  joy_.buttons.resize(BTN_COUNT, 0);
45 
46  ignore_ = false;
47  enable_ = true;
48  count_ = false;
49  svel_ = 0.0;
50  priv_nh.getParam("ignore", ignore_);
51  priv_nh.getParam("enable", enable_);
52  priv_nh.getParam("count", count_);
53  priv_nh.getParam("svel", svel_);
54 
55  sub_joy_ = node.subscribe("/joy", 1, &JoystickDemo::recvJoy, this);
56 
57  data_.brake_joy = 0.0;
58  data_.gear_cmd = dbw_pacifica_msgs::Gear::NONE;
59  data_.steering_joy = 0.0;
60  data_.steering_mult = false;
62  data_.turn_signal_cmd = dbw_pacifica_msgs::TurnSignal::NONE;
64  data_.joy_brake_valid = false;
65 
66  pub_accelerator_pedal_ = node.advertise<dbw_pacifica_msgs::AcceleratorPedalCmd>("accelerator_pedal_cmd", 1);
67  pub_brake_ = node.advertise<dbw_pacifica_msgs::BrakeCmd>("brake_cmd", 1);
68  pub_misc_ = node.advertise<dbw_pacifica_msgs::MiscCmd>("misc_cmd", 1);
69  pub_steering_ = node.advertise<dbw_pacifica_msgs::SteeringCmd>("steering_cmd", 1);
70  pub_global_enable_ = node.advertise<dbw_pacifica_msgs::GlobalEnableCmd>("global_enable_cmd", 1);
71  pub_gear_ = node.advertise<dbw_pacifica_msgs::GearCmd>("gear_cmd", 1);
72  if (enable_) {
73  pub_enable_ = node.advertise<std_msgs::Empty>("enable", 1);
74  pub_disable_ = node.advertise<std_msgs::Empty>("disable", 1);
75  }
76 
78 }
79 
81 {
82  // Detect joy timeouts and reset
83  if (event.current_real - data_.stamp > ros::Duration(0.1)) {
85  data_.joy_brake_valid = false;
86  return;
87  }
88 
89  // Optional watchdog counter
90  if (count_) {
91  counter_++;
92  if (counter_ > 15)
93  {
94  counter_ = 0;
95  }
96  }
97 
98  // Accelerator Pedal
99  dbw_pacifica_msgs::AcceleratorPedalCmd accelerator_pedal_msg;
100  accelerator_pedal_msg.enable = true;
101  accelerator_pedal_msg.ignore = ignore_;
102  accelerator_pedal_msg.rolling_counter = counter_;
103  accelerator_pedal_msg.pedal_cmd = data_.accelerator_pedal_joy * 100;
104  accelerator_pedal_msg.control_type.value = dbw_pacifica_msgs::ActuatorControlMode::open_loop;
105  pub_accelerator_pedal_.publish(accelerator_pedal_msg);
106 
107  // Brake
108  dbw_pacifica_msgs::BrakeCmd brake_msg;
109  brake_msg.enable = true;
110  brake_msg.rolling_counter = counter_;
111  brake_msg.pedal_cmd = data_.brake_joy * 100;
112  brake_msg.control_type.value = dbw_pacifica_msgs::ActuatorControlMode::open_loop;
113  pub_brake_.publish(brake_msg);
114 
115  // Steering
116  dbw_pacifica_msgs::SteeringCmd steering_msg;
117  steering_msg.enable = true;
118  steering_msg.ignore = ignore_;
119  steering_msg.rolling_counter = counter_;
120  steering_msg.angle_cmd = data_.steering_joy;
121  steering_msg.angle_velocity = svel_;
122  steering_msg.control_type.value = dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator;
123  if (!data_.steering_mult) {
124  steering_msg.angle_cmd *= 0.5;
125  }
126  pub_steering_.publish(steering_msg);
127 
128  // Gear
129  dbw_pacifica_msgs::GearCmd gear_msg;
130  gear_msg.cmd.gear = data_.gear_cmd;
131  gear_msg.enable = true;
132  gear_msg.rolling_counter = counter_;
133  pub_gear_.publish(gear_msg);
134 
135  // Turn signal
136  dbw_pacifica_msgs::MiscCmd misc_msg;
137  misc_msg.cmd.value = data_.turn_signal_cmd;
138  misc_msg.rolling_counter = counter_;
139  pub_misc_.publish(misc_msg);
140 
141  dbw_pacifica_msgs::GlobalEnableCmd globalEnable_msg;
142  globalEnable_msg.global_enable = true;
143  globalEnable_msg.enable_joystick_limits = true;
144  globalEnable_msg.rolling_counter = counter_;
145  pub_global_enable_.publish(globalEnable_msg);
146 }
147 
148 void JoystickDemo::recvJoy(const sensor_msgs::Joy::ConstPtr& msg)
149 {
150  // Check for expected sizes
151  if (msg->axes.size() != (size_t)AXIS_COUNT) {
152  ROS_ERROR("Expected %zu joy axis count, received %zu", (size_t)AXIS_COUNT, msg->axes.size());
153  return;
154  }
155  if (msg->buttons.size() != (size_t)BTN_COUNT) {
156  ROS_ERROR("Expected %zu joy button count, received %zu", (size_t)BTN_COUNT, msg->buttons.size());
157  return;
158  }
159 
160  // Handle joystick startup
161  if (msg->axes[AXIS_ACCELERATOR_PEDAL] != 0.0) {
163  }
164  if (msg->axes[AXIS_BRAKE] != 0.0) {
165  data_.joy_brake_valid = true;
166  }
167 
168  // Accelerator pedal
170  data_.accelerator_pedal_joy = 0.5 - 0.5 * msg->axes[AXIS_ACCELERATOR_PEDAL];
171  }
172 
173  // Brake
174  if (data_.joy_brake_valid) {
175  data_.brake_joy = 0.5 - 0.5 * msg->axes[AXIS_BRAKE];
176  }
177 
178  // Gear
179  if (msg->buttons[BTN_PARK]) {
180  data_.gear_cmd = dbw_pacifica_msgs::Gear::PARK;
181  } else if (msg->buttons[BTN_REVERSE]) {
182  data_.gear_cmd = dbw_pacifica_msgs::Gear::REVERSE;
183  } else if (msg->buttons[BTN_DRIVE]) {
184  data_.gear_cmd = dbw_pacifica_msgs::Gear::DRIVE;
185  } else if (msg->buttons[BTN_NEUTRAL]) {
186  data_.gear_cmd = dbw_pacifica_msgs::Gear::NEUTRAL;
187  } else {
188  data_.gear_cmd = dbw_pacifica_msgs::Gear::NONE;
189  }
190 
191  // Steering
192  data_.steering_joy = 470.0 * M_PI / 180.0 * ((fabs(msg->axes[AXIS_STEER_1]) > fabs(msg->axes[AXIS_STEER_2])) ? msg->axes[AXIS_STEER_1] : msg->axes[AXIS_STEER_2]);
193  data_.steering_mult = msg->buttons[BTN_STEER_MULT_1] || msg->buttons[BTN_STEER_MULT_2];
194 
195  // Turn signal
196  if (msg->axes[AXIS_TURN_SIG] != joy_.axes[AXIS_TURN_SIG]) {
197  switch (data_.turn_signal_cmd) {
198  case dbw_pacifica_msgs::TurnSignal::NONE:
199  if (msg->axes[AXIS_TURN_SIG] < -0.5) {
200  data_.turn_signal_cmd = dbw_pacifica_msgs::TurnSignal::RIGHT;
201  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
202  data_.turn_signal_cmd = dbw_pacifica_msgs::TurnSignal::LEFT;
203  }
204  break;
205  case dbw_pacifica_msgs::TurnSignal::LEFT:
206  if (msg->axes[AXIS_TURN_SIG] < -0.5) {
207  data_.turn_signal_cmd = dbw_pacifica_msgs::TurnSignal::RIGHT;
208  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
209  data_.turn_signal_cmd = dbw_pacifica_msgs::TurnSignal::NONE;
210  }
211  break;
212  case dbw_pacifica_msgs::TurnSignal::RIGHT:
213  if (msg->axes[AXIS_TURN_SIG] < -0.5) {
214  data_.turn_signal_cmd = dbw_pacifica_msgs::TurnSignal::NONE;
215  } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
216  data_.turn_signal_cmd = dbw_pacifica_msgs::TurnSignal::LEFT;
217  }
218  break;
219  }
220  }
221 
222  // Optional enable and disable buttons
223  if (enable_) {
224  const std_msgs::Empty empty;
225  if (msg->buttons[BTN_ENABLE]) {
226  pub_enable_.publish(empty);
227  }
228  if (msg->buttons[BTN_DISABLE]) {
229  pub_disable_.publish(empty);
230  }
231  }
232 
234  joy_ = *msg;
235 }
236 
237 }
ros::Publisher pub_enable_
Definition: JoystickDemo.h:78
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())
JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
ros::Publisher pub_global_enable_
Definition: JoystickDemo.h:80
JoystickDataStruct data_
Definition: JoystickDemo.h:90
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::Subscriber sub_joy_
Definition: JoystickDemo.h:72
ros::Publisher pub_steering_
Definition: JoystickDemo.h:75
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getParam(const std::string &key, std::string &s) const
void recvJoy(const sensor_msgs::Joy::ConstPtr &msg)
static Time now()
void cmdCallback(const ros::TimerEvent &event)
ros::Publisher pub_accelerator_pedal_
Definition: JoystickDemo.h:73
ros::Publisher pub_disable_
Definition: JoystickDemo.h:79
#define ROS_ERROR(...)


dbw_pacifica_joystick_demo
Author(s): Jane Doe
autogenerated on Mon Apr 8 2019 02:29:48