Robo Explorer ROS Connector

Package Summary

This is a ROS Stack to control the fischertechnik Robo Explorer with ROS using liboboint.

You need to use the Robo Explorer with Wheels instead of Tracks because the Tracks are too inaccurate for Odometry. I used the Wheel Setup from Mobile Robots 2.

Tutorials

See https://github.com/nxdefiant/ros_roboint

Nodes

libft_adapter

libft_adapter accesses the Interface over libroboint.

Published Topics

ft/get_inputs - (bool[8] inputs, int8[8] outputs, AX, AY, A1, A2, AV, D1, D2 - all int16)

  • Digital (Count from zero) and Analog Inputs of the Robo Interface. The current output states are included.

Subscribed Topics

ft/set_output - (num (int32), speed (int32))

  • Individual Outputs of the Robo Interface (Count from zero)

ft/set_motor - (num (int32), speed (int32))

  • Motor Outputs of the Robo Interface (Count from zero)

Parameters

robo_explorer.py

robo_explorer.py provides the Robo Explorer functions. Publishes ft/set_motor and subscribes to ft/get_inputs

Published Topics

scan - (sensor_msgs/LaserScan)

  • Laserscan data faked by the Sonar Sensor.

odom - (nav_msgs/Odometry)

  • Odometry information.

Subscribed Topics

cmd_vel - (geometry_msgs/Twist)

  • Celocity commands.

Parameters

~ultrasonic_laser - (boolean, default: True)

  • Fake laser scan with ultra sonic range finder.

~wheel_dist - (float, default: 0.1855)

  • Distance between both wheels in meter.

~wheel_size - (float, default: 0.02575)

  • Size of wheel Diameter in meter. Default: (5.15cm) * gear ratio (0.5) = 2.575cm

~speed_gradiant - (float, default: 64.3)

  • Speed to PWM equation gradiant (The m in pwm = speed*m+b)

~speed_constant - (float, default: -1.7)

  • Speed to PWM equation constant (The b in pwm = speed*m+b)

Wiki: Robots/RoboInt (last edited 2013-09-05 19:52:30 by ErikAndresen)