Seekur Software ( Ubuntu 16.04) - ITVRoC/SeekurJr GitHub Wiki

SeekurJr connection

OBS: To use all the devices avaliable, you will need to have access to SeekurJr and Seekur2 (An external computer for graphics processing).

Comunication

Setting the route through the Seekur jr IP:

    $  sudo ip route add 10.0.125.0/24 via 10.0.126.1

Login to the Seekur Jr server :

   $   ssh [email protected]
        password: seekurjr

Login to the Seekur2 server :

   $   ssh [email protected]
        password: seekur2

Packages

To work with SEEKUR JR within the ROS system, it was necessary to search for packages with drivers that offer control over the platform, Schunk arm and other devices (Stereo and PTZ Cameras, GPS, Laser, Bumpers, IMU)

The main packages are:

  • Rosaria: packets that interface with the Aria and Arnl system to communicate with SEEKUR JR.
  • p2os: Package to control the engines of the mobile platform through speed commands. It provides interface for teleoperation through keyboard or joystick.
  • schunk robotics: Driver and Schunk arm controller. The controller acts on the joint space using spline interpolation.
  • MoveIt!: Plan trajectory with detour of obstacles and sends to the Schunk arm controller. Provides graphical interface and a variety of obstacle trajectory path planning algorithms.
  • LMS1xx: Reads the angle and distance values ​​provided by the laser LMS111.
  • gscam: Displays the images captured by the PTZ .
  • ZED stereo camera: The ZED is a camera with dual lenses. It captures high-definition 3D video with a wide field of view and outputs two synchronized left and right video streams in side-by-side format on USB 3.0. The ZED ROS wrapper lets you use the ZED stereo cameras with ROS.
  • seekurjr_description: description of Seekur Jr in URDF format(Unified Robot Description Format)

Packages can be executed directly using the command: rosrun package_name node_name or through launch files roslaunch package_name launch_name.launch

OBS Due to the mobile robots site being off the air, it is possible to access it only by cache:Main page ou categories

Running the packages

ARIA INTERFACE (ROSARIA/ROSARNL)

   $ rosrun rosaria RosAria _port:=/dev/ttyS0

Description: In the ROSARIA package are created topics that demonstrate the status of some SEEKUR JR devices such as bumpers and battery.For more information Aria Manual

   $ rosrun rosarnl rosarnl_node

Description: In the ROS-ARNL package topics are created to help in the mapping and navigation of SEEKUR JR through values ​​of odometry and laser reading.

OBS: The ARIA (rosaria / rosarnl) system interface packages use the ttyS0 serial port. This port is also used by the P2OS_Driver package. Therefore, for compatibility reasons, ARIA system packages are not widely used.

TELEOPERATION

To teleoperate the Seekur, it is necessary to first run the Rosaria package and turn on the motors (press the MOTOR button - The button's LED will be solid on if the motors are enabled). After that, you can publish messages of type cmd_vel to the topic /RosAria/cmd_vel. To do this, you can use a simple package like teleop_twist_keyboard.

In the seekur terminal:

   $ export ROS_MASTER_URI=http://10.0.125.32:11311/
   $ export ROS_IP=10.0.125.32

In the remote pc terminal:

   $ export ROS_MASTER_URI=http://10.0.125.32:11311/
   $ export ROS_IP="remote_machine_ip"
   $ rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=RosAria/cmd_vel

OBS: It's not possible to use the Seekur Jr joystick if you run the Rosaria package.

LASER SICK (LMS1XX)

   $ rosrun lms1xx LMS1xx_node _host:=192.168.0.1

Description: This node is the laser communication driver that creates the topic / scan that receives the laser measurements in the sensor_msgs / LaserScan message format.

NTP CONFIGURATION

SEEKUR JR is configured (/etc/ntp.conf) to be an NTP server client. Thus, by configuring the other machine as a server (/etc/ntp.conf), you can use the command:

   sudo ntpdate -u "remote_pc_IP"

This command must be executed on the SEEKUR JR terminal so that it synchronizes with the other machine.

MAPPING AND NAVIGATION (P2OS)

Mapping and navigation operations need the transformations (/ tf) between the platform components to function. When these packets are run on another machine, there must be clock synchronization between them so that the packets are found at the correct time. For this, the NTP server can be used.

   $ roslaunch p2os_launch pioneerMasterLaunchFile.launch

Description: This launch file consists of several launch files. These launchs basically execute nodes that enable the teleoperation of SEEKUR JR and future mapping of the environment, as described below: p2os_driver: communicates with SEEKUR JR engines and IMU. Generates the base_link → Odom transform. teleop_keyboard: enables teleoperation by keyboard. teleop_joy: enables teleoperation by joystick. sicklms: calls the communication node with the laser described previously (LMS1XX). tf_base_link_to_laser: Generates a static transform between the base_link and the laser.

   $ roslaunch p2os_launch gmapping.launch

Description: This launch executes the mapping node that uses the SLAM technique. The node receives the laser read values ​​through the / scan topic and then generates a map of the environment in the / map topic whose message type is nav_msgs / OccupancyGrid. This package generates the transformed map → odom, which, with the previously generated transforms (odom → base_link → laser), makes it possible to calculate the location of SEEKUR JR within the generated map. The location of SEEKUR JR is published in the / pose topic.

   $ roslaunch p2os_launch navigation.launch

Descrição: This launch consists of other launch files. These launchs are basically settings so that the move_base package performs navigation tasks with obstacle bypass. Before running this launch, you must first run gmapping because the navigation needs a map to work. When executed, navigation generates a local and global cost map. The RVIZ (rosrun rviz rviz) must be used both to visualize the maps and to indicate the trajectory target point. In RVIZ the target point is indicated by the 2D Nav Goal option. By choosing the endpoint where SEEKUR JR should be, the controller will (local_local_base) generate a global and local trajectory. The overall trajectory is directed towards the end point chosen. The local trajectory is directed towards the diversion of obstacles in the regions near SEEKUR JR. Both paths can also be viewed in RVIZ.

Obs: To verify in real time all navigation parameters configured in the move_base, you can use the command "rosrun rqt_reconfigure rqt_reconfigure". Through this tool it is possible to more quickly verify the impact of each parameter on the performance of the robot.

SCHUNK ARM

Required CAN / USB Settings ** OBS: ** Settings must be performed before packages are initialized:

$ can_setup can0 #To configure the Schunk arm
$ can_setup can1 #To configure the Force Torque sensor

or

$ sudo ip link set dev can0 down
$ sudo ip link set can0 type can bitrate 500000
$ sudo ip link set dev can0 up
$ sudo ifconfig can0 txqueuelen 20

Packages use port can0 as default.

Initializing the Schunk arm

To move the SCHUNK arm you should first check if the doors (8 and 29) of the arm have been activated and check if the robot is recharging (If it is, remove the charger cable or turn off the charger). To activate the ports:

    $ seekurPower -8 reset -29 reset

The arm will be ready if the 4 LEDs on the base are on.

First launch to be used, for arm control

roslaunch schunk_lwa4p robot.launch

Starting the service of initialization :

rosservice call /arm/driver/init

The following message should be displayed:

success: True 
message: ''

Package to move the arm

roslaunch lwa4p_movit_config demo.launch

OBS: To use the arm on a remote computer (including seekur2), you must have the LWA4P Moveit package and Schunk robots package in the remote computer.

Run the can configuration, robot.launch and the init service on Seekur, and then, run the moveit launch on the remote computer:

roslaunch lwa4p_movit_config rviz_remote.launch 

If the arm simulation is in a different position from the actual arm position, simply uncheck and check the MotionPlanning topic in Rviz:

Uncheck and check the MotionPlannig box

FORCE TORQUE SENSOR - FTS-LWA

To use the force torque sensor it is necessary to read a calibration file located on src folder. The file is added by a parameter when running the node, so it is necessary to add the path, as seen below:

    $ rosrun fts_lwa force_sensor _private_param_name:=$(rospack find fts_lwa)/src/force_sensor_calib.dat

To view the force and torque graphs, use the launch:

    $ roslaunch fts_lwa force_torque_plot.launch

For more information about the package, see Force Torque Sensor - Seekur Jr

CAMERA PTZ

Before running the PTZ node it is necessary to configure v4l2 for the NTSC format, through the command:

$ v4l2-ctl -s ntsc

In addition, it is necessary to check if port 10 of the SEEKUR JR is activated. To activate the port:

$ seekurPower -10 reset

Launcher for capturing images:

   $ roslaunch gscam camera_raw.launch

Description: Publishes the images of the PTZ camera in a topic of type sensor_msgs / Image. Images can be viewed in the window that opens when executing the node or through RVIZ.

Node for PTZ control:

To control the PTZ camera by the ROS, you must first start the RosAria:

   $ rosrun rosaria RosAria _port:=/dev/ttyS0

Then you must start the Aria interface node:

   $ roslaunch pan_tilt_zoom ptz_control.launch

Description: This node uses the ARIA interface to send pan, tilt, and zoom commands to the camera. The node subscribes to the topic '/ ptz_goal' and when a message arrives at the topic, it calls a callback that sends the command direct to Aria, controlling the PTZ. It also allows you to use the keyboard to move the camera. However using this method, no messages will be published in the topic. Commands are sent directly to the serial port.

to publish a command to PTZ:

   $  rostopic pub -1 /ptz_goal pan_tilt_zoom/pan_tilt_goal  '{pan: 0, tilt: 0, zoom: 0}'

When publishing a message, if the limits of the ptz are exceeded, the value that the camera will receive will be the maximum value.

MAX_PAN = 180 - maximum degrees the unit can pan (clockwise from top).

MIN_PAN = -180 - minimum degrees the unit can pan (counterclockwise from top).

MIN_TILT = -30 - minimum degrees the unit can tilt.

MAX_TILT = 60 - maximum degrees the unit can tilt.

MIN_ZOOM = 0 - minimum value for zoom.

MAX_ZOOM = 32767 - maximum value for zoom.

CAMERA 360

To use this camera, first you will need to turn on the cam in Live mode. Hold down the first and third buttons on the side of the camera simultaneously for approximately 5 seconds, until the "live" led turn on.

In the seekur2 terminal:

  $ spherical_camera ricoh_capture.launch

ZED STEREO CAM

This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras. The stereo cam is connected to the seekur's remote computer "seekur2" . To use zed, you need to run the following commands on the seekur2 terminal.

To launch the ZED wrapper along with an Rviz preview:

$ roslaunch zed_display_rviz display.launch

To launch the wrapper without Rviz, use:

$ roslaunch zed_wrapper zed.launch

For more information, access ZED - Github and ZED - Tutorial and documentation

GPS

Release power to the GPS through port 6 of the SEEKUR JR. through the command:

   $ seekurPower -6 reset

The nmea_navsat_driver replaces nmea_gps_driver to reduce naming conflicts and use new common parsing+driver backend.

To start outputting GPS data onto ROS topics:

   $ rosrun nmea_navsat_driver nmea_serial_driver _port:=/dev/ttyS1 _baud:=38400

Description: This node publishes topics such as position (/fix), speed (/vel), and GPS reference time (/time_reference).

Obs: The GPS needs a minimum of satellites to calculate its position. Inside the ITV lab this number is not reached and GPS does not return correct values. GPS has an application for windows (AgRemote) that generates a diagnosis in more detail. For more information about the GPS configuration see Seekur hardware - GPS