rbcar_joystick.cpp
Go to the documentation of this file.
1 /*
2  * rbcar_joystick
3  * Copyright (c) 2015, Robotnik Automation, SLL
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Robotnik Automation, SLL. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  *
30  * \author Robotnik Automation, SLL
31  * \brief Allows to use a pad with the robot controller, sending the messages received from the joystick device
32  */
33 
34 #include <ros/ros.h>
35 #include <sensor_msgs/Joy.h>
36 #include <geometry_msgs/Twist.h>
37 #include <std_msgs/Int32.h>
38 #include <unistd.h>
39 #include <vector>
40 #include <robotnik_msgs/enable_disable.h>
41 #include <robotnik_msgs/set_digital_output.h>
42 #include "diagnostic_msgs/DiagnosticStatus.h"
47 #include "ackermann_msgs/AckermannDriveStamped.h"
48 #include <std_srvs/Empty.h>
49 #include "robotnik_msgs/set_mode.h"
50 #include "robotnik_msgs/get_mode.h"
51 
52 #define DEFAULT_MAX_LINEAR_SPEED 3.0 //m/s
53 #define DEFAULT_MAX_ANGULAR_POSITION 2.0 // rads/s
54 
55 #define MAX_NUM_OF_BUTTONS 16
56 #define MAX_NUM_OF_AXES 8
57 #define MAX_NUM_OF_BUTTONS_PS3 19
58 #define MAX_NUM_OF_AXES_PS3 20
59 
60 #define DEFAULT_NUM_OF_BUTTONS 16
61 #define DEFAULT_NUM_OF_AXES 8
62 
63 #define DEFAULT_AXIS_LINEAR_X 1
64 #define DEFAULT_AXIS_ANGULAR 2
65 #define DEFAULT_SCALE_LINEAR 1.0
66 #define DEFAULT_SCALE_ANGULAR 1.0
67 
68 #define DEFAULT_JOY "/joy"
69 #define DEFAULT_HZ 50.0
70 
71 
73 class Button{
74  int iPressed;
75  bool bReleased;
76 
77  public:
78 
79  Button(){
80  iPressed = 0;
81  bReleased = false;
82  }
84  void Press(int value){
85  if(iPressed and !value){
86  bReleased = true;
87 
88  }else if(bReleased and value)
89  bReleased = false;
90 
91  iPressed = value;
92 
93  }
94 
95  int IsPressed(){
96  return iPressed;
97  }
98 
99  bool IsReleased(){
100  bool b = bReleased;
101  bReleased = false;
102  return b;
103  }
104 };
105 
106 class RbcarJoy
107 {
108 public:
109  RbcarJoy();
110 
111  void ControlLoop();
112  int SetStateMode(int state, int arm_mode, int platform_mode);
113 
114 private:
115 
116  void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
117 
118  char * StateToString(int state);
119  int SwitchToState(int new_state);
120 
121  void PublishState();
123  bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res );
124  void Update();
125 
126 
127 private:
129 
130  int axis_linear_speed_, axis_angular_position_;
131  double l_scale_, a_scale_;
134  double max_linear_speed_, max_angular_position_;
137 
138  // TOPICS
144  std::string joy_topic_;
146  std::string cmd_topic_vel;
148  std::string cmd_service_io_;
150  std::string topic_state_;
153 
154  // SERVICES
158 
159  // JOYSTICK
163 
165  std::vector<float> fAxes;
167  std::vector<Button> vButtons;
171  int button_speed_up_, button_speed_down_;
172  int output_1_, output_2_;
173  bool bOutput1, bOutput2;
175  int ptz_tilt_up_, ptz_tilt_down_, ptz_pan_right_, ptz_pan_left_;
177  std::string cmd_service_ptz_;
185  std::string cmd_set_mode_;
186 
187  // DIAGNOSTICS
195  double min_freq_command, min_freq_joy;
197  double max_freq_command, max_freq_joy;
199  bool bEnable;
200 };
201 
203  axis_linear_speed_(1),
204  axis_angular_position_(2)
205 {
206  current_speed_lvl = 0.1;
207  //
208  nh_.param("num_of_buttons", num_of_buttons_, DEFAULT_NUM_OF_BUTTONS);
209  nh_.param("num_of_axes", num_of_axes_, DEFAULT_NUM_OF_AXES);
210  nh_.param("desired_freq", desired_freq_, DEFAULT_HZ);
211 
214  ROS_INFO("RbcarJoy::RbcarJoy: Limiting the max number of axes to %d", MAX_NUM_OF_AXES);
215  }
218  ROS_INFO("RbcarJoy::RbcarJoy: Limiting the max number of buttons to %d", MAX_NUM_OF_BUTTONS);
219  }
220 
221  nh_.param("topic_joy", joy_topic_, std::string(DEFAULT_JOY));
222 
223 
224  // MOTION CONF
225  nh_.param("cmd_topic_vel", cmd_topic_vel, std::string("/rbcar_robot_control/command"));
226 
227  nh_.param("button_dead_man", button_dead_man_, button_dead_man_);
228  nh_.param("button_speed_up", button_speed_up_, button_speed_up_);
229  nh_.param("button_speed_down", button_speed_down_, button_speed_down_);
230  nh_.param("max_angular_position", max_angular_position_, DEFAULT_MAX_ANGULAR_POSITION);
231  nh_.param("max_linear_speed_", max_linear_speed_, DEFAULT_MAX_LINEAR_SPEED);
232  nh_.param("axis_linear_speed", axis_linear_speed_, DEFAULT_AXIS_LINEAR_X);
233  nh_.param("axis_angular_position", axis_angular_position_, DEFAULT_AXIS_ANGULAR);
234  ROS_INFO("axis_linear_speed_ = %d, axis_angular = %d", axis_linear_speed_, axis_angular_position_);
235  ROS_INFO("max_linear_speed = %lf, max_angular_speed = %lf", max_linear_speed_, max_angular_position_);
236 
237  // DIGITAL OUTPUTS CONF
238  nh_.param("cmd_service_io", cmd_service_io_, cmd_service_io_);
239  nh_.param("output_1", output_1_, output_1_);
240  nh_.param("output_2", output_2_, output_2_);
241  nh_.param("topic_state", topic_state_, std::string("/rbcar_joystick/state"));
242 
243  // PANTILT CONF
244  nh_.param("cmd_service_ptz", cmd_service_ptz_, cmd_service_ptz_);
245  nh_.param("button_ptz_tilt_up", ptz_tilt_up_, ptz_tilt_up_);
246  nh_.param("button_ptz_tilt_down", ptz_tilt_down_, ptz_tilt_down_);
247  nh_.param("button_ptz_pan_right", ptz_pan_right_, ptz_pan_right_);
248  nh_.param("button_ptz_pan_left", ptz_pan_left_, ptz_pan_left_);
249 
250  // KINEMATIC MODE
251  nh_.param("button_kinematic_mode", button_kinematic_mode_, button_kinematic_mode_);
252  nh_.param("cmd_service_set_mode", cmd_set_mode_, cmd_set_mode_);
253  kinematic_mode_ = 1;
254 
255  ROS_INFO("RbcarJoy num_of_buttons_ = %d, axes = %d, topic controller: %s, hz = %.2lf", num_of_buttons_, num_of_axes_, cmd_topic_vel.c_str(), desired_freq_);
256 
257  for(int i = 0; i < MAX_NUM_OF_BUTTONS_PS3; i++){
258  Button b;
259  vButtons.push_back(b);
260  }
261 
262  for(int i = 0; i < MAX_NUM_OF_AXES_PS3; i++){
263  fAxes.push_back(0.0);
264  }
265 
266  /*
267  // ROS_INFO("Service PTZ = [%s]", cmd_service_ptz_.c_str());
268  ROS_INFO("Service set_mode = [%s]", cmd_set_mode_.c_str());
269  ROS_INFO("Axis linear = %d", linear_);
270  ROS_INFO("Axis angular = %d", angular_);
271  ROS_INFO("Scale angular = %5.2f", a_scale_);
272  ROS_INFO("Deadman button = %d", dead_man_button_);
273  ROS_INFO("OUTPUT1 button %d", button_output_1_);
274  ROS_INFO("OUTPUT2 button %d", button_output_2_);
275  ROS_INFO("OUTPUT1 button %d", button_output_1_);
276  ROS_INFO("OUTPUT2 button %d", button_output_2_);
277  ROS_INFO("Kinematic mode button %d", button_kinematic_mode_);
278  */
279 
280 // HERE
281  this->vel_pub_ = nh_.advertise<ackermann_msgs::AckermannDriveStamped>(this->cmd_topic_vel, 1);
282 
283  // Listen through the node handle sensor_msgs::Joy messages from joystick
284  joy_sub_ = nh_.subscribe<sensor_msgs::Joy>(joy_topic_, 1, &RbcarJoy::joyCallback, this);
285 
286  // Request service to activate / deactivate digital I/O
287  set_digital_outputs_client_ = nh_.serviceClient<robotnik_msgs::set_digital_output>(cmd_service_io_);
288 
289  bOutput1 = bOutput2 = false;
290 
291  // Diagnostics
292  updater_pad.setHardwareID("RbcarJoystick");
293  // Topics freq control
298 
301 
302  // Advertises new service to enable/disable the pad
303  enable_disable_srv_ = nh_.advertiseService("/rbcar_joystick/enable_disable", &RbcarJoy::EnableDisable, this);
304  //
305  bEnable = true; // Communication flag enabled by default
306 
307  // Info message
308  // ROS_INFO("A segfault after this line is usually caused either by bad definition of the pad yaml file or by incrorrect setting of the jsX device in the launch file");
309 }
310 
311 /*
312  * \brief Updates the diagnostic component. Diagnostics
313  * Publishes the state
314  *
315  */
317  PublishState();
318 }
319 
322  /*RbcarJoy::rescuer_pad_state pad_state;
323 
324  pad_state.state = StateToString(iState);
325  pad_state.arm_mode = ModeToString(iArmMode);
326  pad_state.platform_mode = ModeToString(iPlatformMode);
327  pad_state.speed_level = current_speed_lvl;
328  pad_state.deadman_active = (bool) vButtons[button_dead_man_].IsPressed();
329 
330  state_pub_.publish(pad_state);*/
331 }
332 
333 /*
334  * \brief Enables/Disables the pad
335  */
336 bool RbcarJoy::EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res )
337 {
338  bEnable = req.value;
339 
340  ROS_INFO("RbcarJoy::EnablaDisable: Setting to %d", req.value);
341  res.ret = true;
342  return true;
343 }
344 
345 void RbcarJoy::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
346 {
347 
348  // First joystick being saved
349  for(int i = 0; i < joy->axes.size(); i++){
350  this->fAxes[i] = joy->axes[i];
351  }
352  for(int i = 0; i < joy->buttons.size(); i++){
353  this->vButtons[i].Press(joy->buttons[i]);
354  }
355 
356  //ROS_INFO("RbcarJoy::joyCallback: num_of_axes = %d, buttons = %d", (int)(joy->axes.size()), (int)(joy->buttons.size()));
357 }
358 
361 
362  double desired_linear_speed = 0.0, desired_angular_position = 0.0;
363  ackermann_msgs::AckermannDriveStamped ref_msg;
364 
366 
367  while(ros::ok()) {
368 
369  Update();
370 
371  if(bEnable){
372 
373  if(vButtons[button_dead_man_].IsPressed()){
374  ref_msg.header.stamp = ros::Time::now();
375  ref_msg.drive.jerk = 0.0;
376  ref_msg.drive.acceleration = 0.0;
377  ref_msg.drive.steering_angle_velocity = 0.0;
378 
379  desired_linear_speed = max_linear_speed_ * current_speed_lvl * fAxes[axis_linear_speed_];
380  desired_angular_position = max_angular_position_ * fAxes[axis_angular_position_];
381 
382  // ROS_INFO("axis_angular_position_ %d desired_angular_position=%5.2f", axis_angular_position_, desired_angular_position);
383 
384  ref_msg.drive.steering_angle = desired_angular_position;
385  ref_msg.drive.speed = desired_linear_speed;
386 
387  // Publish into command_vel topic
388  vel_pub_.publish(ref_msg);
389 
390  if(vButtons[button_speed_up_].IsReleased()){
391  current_speed_lvl += 0.1;
392  if(current_speed_lvl > 1.0)
393  current_speed_lvl = 1.0;
394  }
395  if(vButtons[button_speed_down_].IsReleased()){
396  current_speed_lvl -= 0.1;
397  if(current_speed_lvl < 0.0)
398  current_speed_lvl = 0.0;
399  }
400 
401  }else if(vButtons[button_dead_man_].IsReleased()){
402  ref_msg.header.stamp = ros::Time::now();
403  ref_msg.drive.jerk = 0.0;
404  ref_msg.drive.acceleration = 0.0;
405  ref_msg.drive.steering_angle_velocity = 0.0;
406 
407  ref_msg.drive.steering_angle = 0.0;
408  ref_msg.drive.speed = 0.0;
409  //ROS_INFO("RbcarJoy::ControlLoop: Deadman released!");
410  vel_pub_.publish(ref_msg);// Publish into command_vel topic
411  }
412  }
413 
414  ros::spinOnce();
415  r.sleep();
416  }
417 }
418 
420 int main(int argc, char** argv)
421 {
422  ros::init(argc, argv, "rbcar_joystick");
423  RbcarJoy joy;
424 
425  joy.ControlLoop();
426 
427 }
428 
429 
ros::Publisher vel_pub_
It will publish into command velocity (for the robot)
int IsPressed()
int axis_angular_position_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int button_speed_down_
void ControlLoop()
Controls the actions and states.
int main(int argc, char **argv)
int button_speed_up_
Number of the button for increase or decrease the speed max of the joystick.
int button_kinematic_mode_
button to change kinematic mode
void publish(const boost::shared_ptr< M > &message) const
double max_linear_speed_
Set the max speed sent to the robot.
#define MAX_NUM_OF_AXES
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setHardwareID(const std::string &hwid)
bool IsReleased()
int ptz_tilt_up_
buttons to the pan-tilt camera
Class to save the state of the buttons.
std::string cmd_service_ptz_
Name of the service to move ptz.
double max_freq_joy
ros::NodeHandle nh_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define DEFAULT_AXIS_ANGULAR
std::vector< float > fAxes
Vector to save the axis values.
std::string joy_topic_
// Name of the joystick&#39;s topic
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
diagnostic_updater::HeaderlessTopicDiagnostic * pub_command_freq
Diagnostic to control the frequency of the published command velocity topic.
#define DEFAULT_MAX_ANGULAR_POSITION
double min_freq_joy
double max_angular_position_
double desired_freq_
Desired component&#39;s freq.
bool bEnable
Flag to enable/disable the communication with the publishers topics.
int button_dead_man_
Number of the DEADMAN button.
#define MAX_NUM_OF_AXES_PS3
ros::ServiceServer enable_disable_srv_
Service clients.
double min_freq_command
Diagnostics min freq.
int axis_linear_speed_
void Press(int value)
Set the button as &#39;pressed&#39;/&#39;released&#39;.
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Publisher state_pub_
Topic to publish the state.
#define MAX_NUM_OF_BUTTONS
bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res)
Enables/Disables the joystick.
bool bReleased
std::string cmd_set_mode_
Name of the service to change the mode.
ROSCPP_DECL bool ok()
#define DEFAULT_HZ
diagnostic_updater::HeaderlessTopicDiagnostic * sus_joy_freq
Diagnostic to control the reception frequency of the subscribed joy topic.
std::vector< Button > vButtons
Vector to save and control the axis values.
void PublishState()
double l_scale_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define DEFAULT_JOY
#define DEFAULT_NUM_OF_BUTTONS
#define DEFAULT_MAX_LINEAR_SPEED
ros::ServiceClient setKinematicMode
Service to modify the kinematic mode.
bool sleep()
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
double current_speed_lvl
ros::ServiceClient set_digital_outputs_client_
std::string cmd_service_io_
Name of the service where it will be modifying the digital outputs.
double max_freq_command
Diagnostics max freq.
std::string cmd_topic_vel
Name of the topic where it will be publishing the velocity.
static Time now()
#define DEFAULT_NUM_OF_AXES
int num_of_buttons_
Current number of buttons of the joystick.
std::string topic_state_
topic name for the state
ROSCPP_DECL void spinOnce()
diagnostic_updater::Updater updater_pad
General status diagnostic updater.
#define MAX_NUM_OF_BUTTONS_PS3
ros::Subscriber joy_sub_
they will be suscribed to the joysticks
#define DEFAULT_AXIS_LINEAR_X
int kinematic_mode_
kinematic mode


rbcar_joystick
Author(s): Roberto Guzman
autogenerated on Mon Jun 10 2019 14:38:44