agvs_pad_node.cpp
Go to the documentation of this file.
1 /*
2  * agvs_pad
3  * Copyright (c) 2013, 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 
35 #include <ros/ros.h>
36 #include <sensor_msgs/Joy.h>
37 #include <geometry_msgs/Twist.h>
38 #include <std_msgs/Int32.h>
39 #include <unistd.h>
40 #include <vector>
41 #include <robotnik_msgs/enable_disable.h>
42 #include <robotnik_msgs/set_digital_output.h>
43 #include "diagnostic_msgs/DiagnosticStatus.h"
48 // #include <agvs_controller/AckermannDriveStamped.h>
49 //#include <agvs_robot_control/AckermannDriveStamped.h>
50 #include "ackermann_msgs/AckermannDriveStamped.h"
51 #include <std_srvs/Empty.h>
52 
53 #define DEFAULT_MAX_SKID_LINEAR_SPEED 2.0 //m/s
54 #define DEFAULT_MAX_ANGULAR_POSITION 2.0 // rads/s
55 
56 #define MAX_NUM_OF_BUTTONS 16
57 #define MAX_NUM_OF_AXES 8
58 #define MAX_NUM_OF_BUTTONS_PS3 19
59 #define MAX_NUM_OF_AXES_PS3 20
60 
61 #define DEFAULT_NUM_OF_BUTTONS 16
62 #define DEFAULT_NUM_OF_AXES 8
63 
64 #define DEFAULT_AXIS_LINEAR_X 1
65 #define DEFAULT_AXIS_ANGULAR 0
66 #define DEFAULT_SCALE_LINEAR 1.0
67 #define DEFAULT_SCALE_ANGULAR 1.0
68 
69 
70 #define DEFAULT_JOY "/joy"
71 
72 #define DEFAULT_HZ 50.0
73 
75 class Button{
76  int iPressed;
77  bool bReleased;
78 
79  public:
80 
81  Button(){
82  iPressed = 0;
83  bReleased = false;
84  }
86  void Press(int value){
87  if(iPressed and !value){
88  bReleased = true;
89 
90  }else if(bReleased and value)
91  bReleased = false;
92 
93  iPressed = value;
94 
95  }
96 
97  int IsPressed(){
98  return iPressed;
99  }
100 
101  bool IsReleased(){
102  bool b = bReleased;
103  bReleased = false;
104  return b;
105  }
106 };
107 
109 // //
111 class AgvsPad
112 {
113  public:
114 
115  AgvsPad();
116 
117  void ControlLoop();
118  int SetStateMode(int state, int arm_mode, int platform_mode);
119 
120  private:
121 
122  void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
123 
124  char * StateToString(int state);
125  int SwitchToState(int new_state);
126 
127  void PublishState();
129  bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res );
130  void Update();
131 
132 private:
133 
135 
136  int axis_linear_speed_, axis_angular_position_;
137  double l_scale_, a_scale_;
140  double max_linear_speed_, max_angular_position_;
143 
144  // TOPICS
147 
151  std::string joy_topic_;
153  std::string cmd_topic_vel;
155  std::string cmd_service_io_;
157  std::string topic_state_;
160 
165 
166  // SERVICES
172 
173 
174  // JOYSTICK
178 
180  std::vector<float> fAxes;
182  std::vector<Button> vButtons;
186  int button_speed_up_, button_speed_down_;
187  int button_up_car_, button_down_car_;
188  int output_1_, output_2_;
189  bool bOutput1, bOutput2;
190 
191  // DIAGNOSTICS
199  double min_freq_command, min_freq_joy;
201  double max_freq_command, max_freq_joy;
203  bool bEnable;
204 };
205 
206 
208  axis_linear_speed_(1),
209  axis_angular_position_(2), nh_("~")
210 {
211 
212  current_speed_lvl = 0.1;
213  // JOYSTICK CONFIG
214  nh_.param("num_of_buttons", num_of_buttons_, DEFAULT_NUM_OF_BUTTONS);
215  nh_.param("num_of_axes", num_of_axes_, DEFAULT_NUM_OF_AXES);
216  nh_.param("desired_freq", desired_freq_, DEFAULT_HZ);
217 
220  ROS_INFO("AgvsPad::AgvsPad: Limiting the max number of axes to %d", MAX_NUM_OF_AXES);
221  }
224  ROS_INFO("AgvsPad::AgvsPad: Limiting the max number of buttons to %d", MAX_NUM_OF_BUTTONS);
225  }
226 
227  nh_.param("topic_joy", joy_topic_, std::string(DEFAULT_JOY));
228 
229  // MOTION CONF
230  nh_.param("cmd_topic_vel", cmd_topic_vel, std::string("/agvs_controller/command"));
231 
232  nh_.param("button_dead_man", button_dead_man_, button_dead_man_);
233  nh_.param("button_speed_up", button_speed_up_, button_speed_up_);
234  nh_.param("button_speed_down", button_speed_down_, button_speed_down_);
235 
236  nh_.param("max_angular_position", max_angular_position_, DEFAULT_MAX_ANGULAR_POSITION);
238  nh_.param("axis_linear_speed", axis_linear_speed_, DEFAULT_AXIS_LINEAR_X);
239  nh_.param("axis_angular_position", axis_angular_position_, DEFAULT_AXIS_ANGULAR);
240  ROS_INFO("axis_linear_speed_ = %d, axis_angular = %d", axis_linear_speed_, axis_angular_position_);
241  ROS_INFO("max_linear_speed = %lf, max_angular_speed = %lf", max_linear_speed_, max_angular_position_);
242 
243  // DIGITAL OUTPUTS CONF
244  nh_.param("cmd_service_io", cmd_service_io_, cmd_service_io_);
245  nh_.param("button_up_car", button_up_car_, button_up_car_);
246  nh_.param("button_down_car", button_down_car_, button_down_car_);
247  nh_.param("output_1", output_1_, output_1_);
248  nh_.param("output_2", output_2_, output_2_);
249 
250  nh_.param("topic_state", topic_state_, std::string("/agvs_pad/state"));
251 
252  nh_.param("service_raise_elevator", service_raise_elevator_, std::string("/agvs_robot_control/raise_elevator"));
253  nh_.param("service_lower_elevator", service_lower_elevator_, std::string("/agvs_robot_control/lower_elevator"));
254 
255  ROS_INFO("AgvsPad 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  // Publish through the node handle Twist type messages to the guardian_controller/command topic
268  //this->vel_pub_ = nh_.advertise<agvs_controller::AckermannDriveStamped>(this->cmd_topic_vel, 1);
269  this->vel_pub_ = nh_.advertise<ackermann_msgs::AckermannDriveStamped>(this->cmd_topic_vel, 1);
270 
271  //
272  // Publishes the state
273  //state_pub_ = nh_.advertise<agvs_pad::rescuer_pad_state>(topic_state_, 1);
274 
275  // Listen through the node handle sensor_msgs::Joy messages from joystick
276  // (these are the references that we will sent to rescuer_controller/command)
277  joy_sub_ = nh_.subscribe<sensor_msgs::Joy>(joy_topic_, 1, &AgvsPad::joyCallback, this);
278 
279  // Request service to activate / deactivate digital I/O
280  set_digital_outputs_client_ = nh_.serviceClient<robotnik_msgs::set_digital_output>(cmd_service_io_);
281 
282  // Request raise or lower the elevator
285 
286 
287  bOutput1 = bOutput2 = false;
288 
289 
290  // Diagnostics
291  updater_pad.setHardwareID("AGVS-PAD");
292  // Topics freq control
297 
300 
301  // Advertises new service to enable/disable the pad
302  enable_disable_srv_ = nh_.advertiseService("/agvs_pad/enable_disable", &AgvsPad::EnableDisable, this);
303  //
304  bEnable = true; // Communication flag enabled by default
305 
306 }
307 
308 
309 /*
310  * \brief Updates the diagnostic component. Diagnostics
311  * Publishes the state
312  *
313  */
315  PublishState();
316 }
317 
320  /*agvs_pad::rescuer_pad_state pad_state;
321 
322 
323  pad_state.state = StateToString(iState);
324  pad_state.arm_mode = ModeToString(iArmMode);
325  pad_state.platform_mode = ModeToString(iPlatformMode);
326  pad_state.speed_level = current_speed_lvl;
327  pad_state.deadman_active = (bool) vButtons[button_dead_man_].IsPressed();
328 
329  state_pub_.publish(pad_state);*/
330 
331 }
332 
333 /*
334  * \brief Enables/Disables the pad
335  *
336  */
337 bool AgvsPad::EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res )
338 {
339  bEnable = req.value;
340 
341  ROS_INFO("AgvsPad::EnablaDisable: Setting to %d", req.value);
342  res.ret = true;
343  return true;
344 }
345 
346 
347 void AgvsPad::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
348 {
349 
350  // First joystick being saved
351  for(int i = 0; i < joy->axes.size(); i++){
352  this->fAxes[i] = joy->axes[i];
353  }
354  for(int i = 0; i < joy->buttons.size(); i++){
355  this->vButtons[i].Press(joy->buttons[i]);
356  }
357 
358  //ROS_INFO("AgvsPad::joyCallback: num_of_axes = %d, buttons = %d", (int)(joy->axes.size()), (int)(joy->buttons.size()));
359 }
360 
361 
364  double desired_linear_speed = 0.0, desired_angular_position = 0.0;
365  //agvs_controller::AckermannDriveStamped ref_msg;
366  ackermann_msgs::AckermannDriveStamped ref_msg;
367 
368 
370 
371  while(ros::ok()) {
372 
373  Update();
374 
375  if(bEnable){
376 
377  if(vButtons[button_dead_man_].IsPressed()){
378  ref_msg.header.stamp = ros::Time::now();
379  ref_msg.drive.jerk = 0.0;
380  ref_msg.drive.acceleration = 0.0;
381  ref_msg.drive.steering_angle_velocity = 0.0;
382 
383  desired_linear_speed = max_linear_speed_ * current_speed_lvl * fAxes[axis_linear_speed_];
384  desired_angular_position = max_angular_position_ * fAxes[axis_angular_position_];
385 
386  ref_msg.drive.steering_angle = desired_angular_position;
387  ref_msg.drive.speed = desired_linear_speed;
388 
389  // Publish into command_vel topic
390  vel_pub_.publish(ref_msg);
391 
392  if(vButtons[button_speed_up_].IsReleased()){
393  current_speed_lvl += 0.1;
394  if(current_speed_lvl > 1.0)
395  current_speed_lvl = 1.0;
396  }
397  if(vButtons[button_speed_down_].IsReleased()){
398  current_speed_lvl -= 0.1;
399  if(current_speed_lvl < 0.0)
400  current_speed_lvl = 0.0;
401  }
402 
403 
404  }else if(vButtons[button_dead_man_].IsReleased()){
405  ref_msg.header.stamp = ros::Time::now();
406  ref_msg.drive.jerk = 0.0;
407  ref_msg.drive.acceleration = 0.0;
408  ref_msg.drive.steering_angle_velocity = 0.0;
409 
410  ref_msg.drive.steering_angle = 0.0;
411  ref_msg.drive.speed = 0.0;
412  //ROS_INFO("AgvsPad::ControlLoop: Deadman released!");
413  vel_pub_.publish(ref_msg);// Publish into command_vel topic
414  }
415  if (vButtons[button_up_car_].IsReleased()){
416  std_srvs::Empty empty_srv;
417  raise_elevator_client_.call( empty_srv );
418  ROS_INFO("Raise elevator");
419  }
420  if (vButtons[button_down_car_].IsReleased()){
421  std_srvs::Empty empty_srv;
422  lower_elevator_client_.call( empty_srv );
423  ROS_INFO("Lower elevator");
424  }
425  }
426 
427  ros::spinOnce();
428  r.sleep();
429  }
430 
431 }
432 
433 
435 int main(int argc, char** argv)
436 {
437  ros::init(argc, argv, "agvs_pad");
438  AgvsPad pad;
439 
440  pad.ControlLoop();
441 
442 }
443 
bool bEnable
Flag to enable/disable the communication with the publishers topics.
int IsPressed()
void ControlLoop()
Controls the actions and states.
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
#define MAX_NUM_OF_AXES
std::vector< float > fAxes
Vector to save the axis values.
int axis_angular_position_
std::string joy_topic_
// Name of the joystick&#39;s topic
void publish(const boost::shared_ptr< M > &message) const
std::string topic_state_
topic name for the state
int button_dead_man_
Number of the DEADMAN button.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double l_scale_
ros::ServiceServer enable_disable_srv_
Service clients.
ros::ServiceClient raise_elevator_client_
ros::ServiceClient set_digital_outputs_client_
#define DEFAULT_MAX_SKID_LINEAR_SPEED
void setHardwareID(const std::string &hwid)
ros::NodeHandle nh_
bool IsReleased()
#define DEFAULT_NUM_OF_BUTTONS
Class to save the state of the buttons.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
std::vector< Button > vButtons
Vector to save and control the axis values.
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.
std::string service_lower_elevator_
Name of the service called to lower the elevator.
void Update()
#define DEFAULT_NUM_OF_AXES
#define DEFAULT_AXIS_ANGULAR
std::string cmd_service_io_
Name of the service where it will be modifying the digital outputs.
#define DEFAULT_MAX_ANGULAR_POSITION
int num_of_axes_
int button_up_car_
int axis_linear_speed_
double min_freq_command
Diagnostics min freq.
#define DEFAULT_HZ
#define DEFAULT_AXIS_LINEAR_X
double max_linear_speed_
Set the max speed sent to the robot.
void Press(int value)
Set the button as &#39;pressed&#39;/&#39;released&#39;.
ros::Publisher state_pub_
Topic to publish the state.
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int iPressed
bool bReleased
ROSCPP_DECL bool ok()
ros::Subscriber joy_sub_
they will be suscribed to the joysticks
diagnostic_updater::Updater updater_pad
General status diagnostic updater.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher vel_pub_
It will publish into command velocity (for the robot)
double current_speed_lvl
diagnostic_updater::HeaderlessTopicDiagnostic * sus_joy_freq
Diagnostic to control the reception frequency of the subscribed joy topic.
bool sleep()
#define MAX_NUM_OF_AXES_PS3
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
double desired_freq_
Desired component&#39;s freq.
static Time now()
double max_freq_joy
double min_freq_joy
#define MAX_NUM_OF_BUTTONS
double max_freq_command
Diagnostics max freq.
int button_speed_up_
Number of the button for increase or decrease the speed max of the joystick.
int num_of_buttons_
Current number of buttons of the joystick.
std::string cmd_topic_vel
Name of the topic where it will be publishing the velocity.
ros::ServiceClient lower_elevator_client_
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
std::string service_raise_elevator_
Name of the service called to raise the elevator.
int button_speed_down_
bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res)
Enables/Disables the joystick.
#define DEFAULT_JOY
#define MAX_NUM_OF_BUTTONS_PS3
int button_down_car_
double max_angular_position_
void PublishState()


agvs_pad
Author(s): Román Navarro
autogenerated on Mon Jun 10 2019 12:41:14