Only released in EOL distros:  

Overview

Package contains node for teleoperating Care-O-Bot or any other holonomic robot by Space Navigator 3D mouse.

Control input from SN is recomputed to make robot teleoperation in user perspective. This helps to lower mental load of an operator and leads to very intuitive way of interaction. To enable this functionality position of RVIZ camera must be published as TF transformation for instance, by plugin from srs_env_model_ui.

Node can publish to two Twist topics. Normally it publish to first one (safe topic in case of Care-O-Bot) and when the left button is pressed on SN, it publishes to second topic (unsafe in case of Care-O-Bot). When right button is pressed once, robot control is switched to the robot perspective. Next press will switch control back to default mode.

Teleop node also offers axis preference which can be useful for some robot bases. This means if user tries to command robot to move in x axis direction for instance, then in some cases (depending on the parameters) small movements in other axes can be ignored.

ROS API

Subscribed Topics

/spacenav/offset (geometry_msgs/Vector3)
  • Space Navigator topic.
/spacenav/rot_offset (geometry_msgs/Vector3)
  • Space Navigator topic.
/spacenav/joy (sensor_msgs/Joy)
  • Space Navigator topic.

Published Topics

/cmd_vel_safe (geometry_msgs/Twist)
  • Commands are published to this topic by default.
/cmd_vel_unsafe (geometry_msgs/Twist)
  • Commands are published to this topic while the left button is pressed.

Services

~disable (std_srvs/Empty)
  • Disables SN teleop so, it can be used as a control for different task.
~enable (std_srvs/Empty)
  • Enables previously disabled SN teleop.

Parameters

~max_vel_x (double, default: "0.3")
  • Maximal translational velocity in "x" axis.
~max_vel_y (double, default: "0.2")
  • Maximal translational velocity in "y" axis.
~max_vel_th (double, default: "0.3")
  • Maximal rotational velocity in "z" (theta) axis.
~spacenav/max_val (double, default: "350.0")
  • Maximal value on offset/rot_offset topic.
~spacenav/min_val_th (double, default: "0.05")
  • Lower values (normalized to 0-1 range) will be ignored.
~spacenav/ignore_th_high (double, default: "0.9")
  • Upper threshold for axis preference. If user's effort' to move robot in any axis is higher than this threshold and in all other axes lower then ignore_th_low, then one axis will be prefered and others ignored - setted to zero.
~spacenav/ignore_th_low (double, default: "0.1")
  • Lower threshold for axis preference.
~spacenav/instant_stop_enabled (bool, default: "false")
  • When enabled, robot can be stopped by pressing SN. Teleop will then publish zero velocities for few seconds.
~use_rviz_cam (bool, default: "false")
  • Enables/disables usage of RVIZ camera position to transform control commands according to it.
~rviz_cam_link (string, default: "/rviz_cam")
  • RVIZ camera TF frame.

Usage example

To test with simulated Care-O-Bot run following command:

roslaunch cob_spacenav_teleop spacenav_teleop_test_sim.launch

To test with a real robot, connect SN and launch its driver:

rosrun spacenav_node spacenav_node

Launch teleop:

roslaunch cob_spacenav_teleop spacenav_teleop.launch

Wiki: cob_spacenav_teleop (last edited 2013-04-08 09:26:12 by ZdenekMaterna)