42 #include "geometry_msgs/Vector3.h" 43 #include "geometry_msgs/Twist.h" 44 #include "sensor_msgs/Joy.h" 55 if (param.size() == 0)
62 if (param.size() == 3)
66 if (param.size() == 1)
68 param.push_back(param[0]);
69 param.push_back(param[0]);
75 int main(
int argc,
char **argv)
88 private_nh.param<
double>(
"full_scale", full_scale, 512);
89 if (full_scale < 1e-10)
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));
103 <<
"/linear_scale must have either one or three components.");
109 <<
"/angular_scale must have either one or three components.");
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]);
115 if (spnav_open() == -1)
117 ROS_ERROR(
"Could not open the space navigator device. " 118 "Did you remember to run spacenavd (as root)?");
125 int static_count_threshold = 30;
129 bool zero_when_static =
true;
135 double static_trans_deadband = 0.1;
136 double static_rot_deadband = 0.1;
140 sensor_msgs::Joy joystick_msg;
141 joystick_msg.axes.resize(6);
142 joystick_msg.buttons.resize(2);
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;
154 while (node_handle.
ok())
156 bool joy_stale =
false;
157 bool queue_empty =
false;
165 switch (spnav_poll_event(&sev))
170 if (++no_motion_count > static_count_threshold)
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)
178 normed_vx = normed_vy = normed_vz = 0;
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)
187 normed_wx = normed_wy = normed_wz = 0;
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;
200 normed_wx = sev.motion.rz / full_scale;
201 normed_wy = -sev.motion.rx / full_scale;
202 normed_wz = sev.motion.ry / full_scale;
207 case SPNAV_EVENT_BUTTON:
208 joystick_msg.buttons[sev.button.bnum] = sev.button.press;
213 ROS_WARN(
"Unknown message type in spacenav. This should never happen.");
217 if (motion_stale && (queue_empty || joy_stale))
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);
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);
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;
245 motion_stale =
false;
251 joy_pub.publish(joystick_msg);
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
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)
#define ROS_ERROR_STREAM(args)
bool ensureThreeComponents(std::vector< double > ¶m)