roch_xbox_joy.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 #include <geometry_msgs/Twist.h>
32 #include <sensor_msgs/Joy.h>
33 #include "boost/thread/mutex.hpp"
34 #include "boost/thread/thread.hpp"
35 #include "ros/console.h"
36 
38 {
39 public:
41 
42 private:
43  void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
44  void publish();
45 
47 
50  double l_scale_, a_scale_;
54 
55  geometry_msgs::Twist last_published_;
56  boost::mutex publish_mutex_;
60 
61 };
62 
64  ph_("~"),
65  linear_(1),
66  angular_(0),
67  forward_(3),
68  back_(0),
69  left_(2),
70  right_(1),
71  deadman_axis_(4),
72  l_scale_(0.3),
73  a_scale_(0.9),
74  linear_speed_(0.5),
75  angular_speed_(2.5)
76 {
77  ph_.param("axis_linear", linear_, linear_);
78  ph_.param("axis_angular", angular_, angular_);
79  ph_.param("axis_forward", forward_, forward_);
80  ph_.param("axis_back", back_, back_);
81  ph_.param("axis_left", left_, left_);
82  ph_.param("axis_right", right_, right_);
83  ph_.param("axis_deadman", deadman_axis_, deadman_axis_);
84  ph_.param("scale_angular", a_scale_, a_scale_);
85  ph_.param("scale_linear", l_scale_, l_scale_);
86  ph_.param("linear_speed", linear_speed_, linear_speed_);
87  ph_.param("angular_speed", angular_speed_, angular_speed_);
88 
89  deadman_pressed_ = false;
90  zero_twist_published_ = false;
91 
92  vel_pub_ = ph_.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);
93  joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &RochXboxTeleop::joyCallback, this);
94 
95  timer_ = nh_.createTimer(ros::Duration(0.1), boost::bind(&RochXboxTeleop::publish, this));
96 }
97 
98 void RochXboxTeleop::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
99 {
100  geometry_msgs::Twist vel;
101  if( (a_scale_*joy->axes[angular_] != 430) || (l_scale_*joy->axes[linear_] != 255) ){
102  vel.angular.z = a_scale_*joy->axes[angular_];
103  vel.linear.x = l_scale_*joy->axes[linear_];
104  }
105  if( joy->buttons[forward_]){
106  vel.angular.z = 0;
107  vel.linear.x = linear_speed_;
108  }
109  if( joy->buttons[back_]){
110  vel.angular.z = 0;
111  vel.linear.x = -linear_speed_;
112  }
113  if( joy->buttons[left_]){
114  vel.angular.z = angular_speed_;
115  vel.linear.x = 0;
116  }
117  if( joy->buttons[right_]){
118  vel.angular.z = -angular_speed_;
119  vel.linear.x = 0;
120  }
121  last_published_ = vel;
122  deadman_pressed_ = joy->buttons[deadman_axis_];
123 }
124 
126 {
127  boost::mutex::scoped_lock lock(publish_mutex_);
128 
129  if (deadman_pressed_)
130  {
132  zero_twist_published_=false;
133  }
135  {
136  vel_pub_.publish(*new geometry_msgs::Twist());
138  }
139 }
140 
141 int main(int argc, char** argv)
142 {
143  ros::init(argc, argv, "roch_teleop");
144  RochXboxTeleop husky_xbox_teleop;
145 
146  ros::spin();
147 }
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())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::mutex publish_mutex_
ros::NodeHandle ph_
ROSCPP_DECL void spin(Spinner &spinner)
ros::NodeHandle nh_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Subscriber joy_sub_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
bool zero_twist_published_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Timer timer_
int main(int argc, char **argv)
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
geometry_msgs::Twist last_published_
ros::Publisher vel_pub_


roch_teleop
Author(s): Chen
autogenerated on Mon Jun 10 2019 14:44:16