spacenav_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 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 /*
31  * Author: Stuart Glaser
32  */
33 
34 #include <cstdio>
35 #include <vector>
36 
37 #include "ros/node_handle.h"
38 #include "ros/param.h"
39 
40 #include "spnav.h" // NOLINT
41 
42 #include "geometry_msgs/Vector3.h"
43 #include "geometry_msgs/Twist.h"
44 #include "sensor_msgs/Joy.h"
45 
53 bool ensureThreeComponents(std::vector<double>& param)
54 {
55  if (param.size() == 0)
56  {
57  param.push_back(1);
58  param.push_back(1);
59  param.push_back(1);
60  return True;
61  }
62  if (param.size() == 3)
63  {
64  return True;
65  }
66  if (param.size() == 1)
67  {
68  param.push_back(param[0]);
69  param.push_back(param[0]);
70  return True;
71  }
72  return False;
73 }
74 
75 int main(int argc, char **argv)
76 {
77  ros::init(argc, argv, "spacenav");
78 
79  ros::NodeHandle node_handle;
80  ros::Publisher offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/offset", 2);
81  ros::Publisher rot_offset_pub = node_handle.advertise<geometry_msgs::Vector3>("spacenav/rot_offset", 2);
82  ros::Publisher twist_pub = node_handle.advertise<geometry_msgs::Twist>("spacenav/twist", 2);
83  ros::Publisher joy_pub = node_handle.advertise<sensor_msgs::Joy>("spacenav/joy", 2);
84 
85  // Used to scale joystick output to be in [-1, 1]. Estimated from data, and not necessarily correct.
86  ros::NodeHandle private_nh("~");
87  double full_scale;
88  private_nh.param<double>("full_scale", full_scale, 512);
89  if (full_scale < 1e-10)
90  {
91  full_scale = 512;
92  }
93  // Scale factors for the different axes. End output will be within [-scale, +scale], provided
94  // full_scale normalizes to within [-1, 1].
95  std::vector<double> linear_scale;
96  std::vector<double> angular_scale;
97  private_nh.param<std::vector<double> >("linear_scale", linear_scale, std::vector<double>(3, 1));
98  private_nh.param<std::vector<double> >("angular_scale", angular_scale, std::vector<double>(3, 1));
99 
100  if (!ensureThreeComponents(linear_scale))
101  {
102  ROS_ERROR_STREAM("Parameter " << private_nh.getNamespace()
103  << "/linear_scale must have either one or three components.");
104  exit(EXIT_FAILURE);
105  }
106  if (!ensureThreeComponents(angular_scale))
107  {
108  ROS_ERROR_STREAM("Parameter " << private_nh.getNamespace()
109  << "/angular_scale must have either one or three components.");
110  exit(EXIT_FAILURE);
111  }
112  ROS_DEBUG("linear_scale: %.3f %.3f %.3f", linear_scale[0], linear_scale[1], linear_scale[2]);
113  ROS_DEBUG("angular_scale: %.3f %.3f %.3f", angular_scale[0], angular_scale[1], angular_scale[2]);
114 
115  if (spnav_open() == -1)
116  {
117  ROS_ERROR("Could not open the space navigator device. "
118  "Did you remember to run spacenavd (as root)?");
119 
120  return 1;
121  }
122 
123  // Parameters
124  // The number of polls needed to be done before the device is considered "static"
125  int static_count_threshold = 30;
126  ros::param::get("~/static_count_threshold", static_count_threshold);
127 
128  // If true, the node will zero the output when the device is "static"
129  bool zero_when_static = true;
130  ros::param::get("~/zero_when_static", zero_when_static);
131 
132  // If the device is considered "static" and each trans, rot normed component
133  // is below the deadband, it will output zeros in either rotation,
134  // translation, or both.
135  double static_trans_deadband = 0.1;
136  double static_rot_deadband = 0.1;
137  ros::param::get("~/static_trans_deadband", static_trans_deadband);
138  ros::param::get("~/static_rot_deadband", static_rot_deadband);
139 
140  sensor_msgs::Joy joystick_msg;
141  joystick_msg.axes.resize(6);
142  joystick_msg.buttons.resize(2);
143 
144  spnav_event sev;
145  int no_motion_count = 0;
146  bool motion_stale = false;
147  double normed_vx = 0;
148  double normed_vy = 0;
149  double normed_vz = 0;
150  double normed_wx = 0;
151  double normed_wy = 0;
152  double normed_wz = 0;
153 
154  while (node_handle.ok())
155  {
156  bool joy_stale = false;
157  bool queue_empty = false;
158 
159  // Sleep when the queue is empty.
160  // If the queue is empty 30 times in a row output zeros.
161  // Output changes each time a button event happens, or when a motion
162  // event happens and the queue is empty.
163  joystick_msg.header.stamp = ros::Time().now();
164 
165  switch (spnav_poll_event(&sev))
166  {
167  case 0:
168  queue_empty = true;
169 
170  if (++no_motion_count > static_count_threshold)
171  {
172  if (zero_when_static ||
173  (fabs(normed_vx) < static_trans_deadband &&
174  fabs(normed_vy) < static_trans_deadband &&
175  fabs(normed_vz) < static_trans_deadband)
176  )
177  {
178  normed_vx = normed_vy = normed_vz = 0;
179  }
180 
181  if (zero_when_static ||
182  (fabs(normed_wx) < static_rot_deadband &&
183  fabs(normed_wy) < static_rot_deadband &&
184  fabs(normed_wz) < static_rot_deadband)
185  )
186  {
187  normed_wx = normed_wy = normed_wz = 0;
188  }
189 
190  no_motion_count = 0;
191  motion_stale = true;
192  }
193  break;
194 
195  case SPNAV_EVENT_MOTION:
196  normed_vx = sev.motion.z / full_scale;
197  normed_vy = -sev.motion.x / full_scale;
198  normed_vz = sev.motion.y / full_scale;
199 
200  normed_wx = sev.motion.rz / full_scale;
201  normed_wy = -sev.motion.rx / full_scale;
202  normed_wz = sev.motion.ry / full_scale;
203 
204  motion_stale = true;
205  break;
206 
207  case SPNAV_EVENT_BUTTON:
208  joystick_msg.buttons[sev.button.bnum] = sev.button.press;
209  joy_stale = true;
210  break;
211 
212  default:
213  ROS_WARN("Unknown message type in spacenav. This should never happen.");
214  break;
215  }
216 
217  if (motion_stale && (queue_empty || joy_stale))
218  {
219  // The offset and rot_offset are scaled.
220  geometry_msgs::Vector3 offset_msg;
221  offset_msg.x = normed_vx * linear_scale[0];
222  offset_msg.y = normed_vy * linear_scale[1];
223  offset_msg.z = normed_vz * linear_scale[2];
224  offset_pub.publish(offset_msg);
225  geometry_msgs::Vector3 rot_offset_msg;
226  rot_offset_msg.x = normed_wx * angular_scale[0];
227  rot_offset_msg.y = normed_wy * angular_scale[1];
228  rot_offset_msg.z = normed_wz * angular_scale[2];
229  rot_offset_pub.publish(rot_offset_msg);
230 
231  geometry_msgs::Twist twist_msg;
232  twist_msg.linear = offset_msg;
233  twist_msg.angular = rot_offset_msg;
234  twist_pub.publish(twist_msg);
235 
236  // The joystick.axes are normalized within [-1, 1].
237  joystick_msg.axes[0] = normed_vx;
238  joystick_msg.axes[1] = normed_vy;
239  joystick_msg.axes[2] = normed_vz;
240  joystick_msg.axes[3] = normed_wx;
241  joystick_msg.axes[4] = normed_wy;
242  joystick_msg.axes[5] = normed_wz;
243 
244  no_motion_count = 0;
245  motion_stale = false;
246  joy_stale = true;
247  }
248 
249  if (joy_stale)
250  {
251  joy_pub.publish(joystick_msg);
252  }
253 
254  if (queue_empty)
255  {
256  usleep(1000);
257  }
258  }
259 
260  spnav_close();
261 
262  return 0;
263 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
#define ROS_ERROR_STREAM(args)
bool ok() const
#define ROS_ERROR(...)
bool ensureThreeComponents(std::vector< double > &param)
#define ROS_DEBUG(...)


spacenav_node
Author(s): Stuart Glaser, Blaise Gassend
autogenerated on Mon Feb 28 2022 22:37:03