Rob@work mini is a simple demonstration and development platform for navigation strategies from Fraunhofer IPA. The HW development of the rob@work mini is a development based on the open source robot TurtleBot and the data will be made open source here in the RoboPORT repository. The vision of this Project is to create a user community around this robot, which will be able to build their own robots of this type - further developments of their robots will be mirrored back into into this project, to provide them to all. By an increasing demand from the community, it is planed to provide this robot as a toolkit, delivered directly from the sub-manufacturers.
The code for the base controller is based on the turtlebot3_core example and the turtlebot_friends example for mecanumwheels and uses the formulae from this paper for calculating the kinematics (Summary).
The base controller code requires the OpenCR Board by ROBOTIS and is using the turtlebot3_core libraries to set up a ROS Node to communicate with a ROS Master.
The code for the adapted turtlebot core can be found at the IPA fork of the ROBOTIS repository under /examples/turtlebot3_friends/turtlebot3_mecanum_core. It will be tried to feed this back to the main repositoriy to make this code available directly from the turtlebot & friends examples.
Make sure to install the Arduino IDE and the OpenCR libraries by following these Instructions. Then use the Arduino IDE to upload the turtlebot3_mecanum_core.ino file onto the OpenCR board.
The OpenCR Board launches a ROS Node that can be connected to by using the
rosrun rosserial_python serial_node.py
command.
Once the ROS Node is connected, the OpenCR Board publishes and subscribes to various topics listed below:
Topic Name | Type | Description |
---|---|---|
sensor_state |
turtlebot3_msgs::SensorState |
|
version_info |
turtlebot3_msgs::VersionInfo |
|
cmd_vel_rc100 |
geometry_msgs::Twist |
|
odom |
nav_msgs::Odometry |
|
joint_states |
sensor_msgs::JointState |
|
battery_state |
sensor_msgs::BatteryState |
|
magnetic_field |
sensor_msgs::MagneticField |
Topic Name | Type | Description |
---|---|---|
cmd_vel |
geometry_msgs::Twist |
Used to command the motors of the robot |
sound |
turtlebot3_msgs::Sound |
Plays a set of predefined sounds on the OpenCR Board |
motor_power |
std_msgs::Bool |
Turns the motors on or off |
reset |
std_msgs::Empty |
Resets the board |
The following code lines need to be modified in the [turtlebot3mecanum_core_config.h](turtlebot3_mecanum_core_config.h) and turtlebot3_mecanum_core_motor_driver files: _Note: you might also want to change the Topic names that the OpenCR Board subscribes and publishes. This can be done in the core file.
turtlebot3_mecanum_core_config.h
//the radius of the wheels
#define WHEEL_RADIUS 0.1 // meter
//half the distance between the front left and front right wheel
#define WHEEL_SEPARATION_X 0.09 // meter
//half the distance between the front and the rear wheels
#define WHEEL_SEPARATION_Y 0.115 // meter
turtlebot3_mecanm_core_motor_driver.h
#define DXL_LEFT_REAR_ID 3 // ID of left rear motor
#define DXL_RIGHT_REAR_ID 4 // ID of right rear motor
#define DXL_LEFT_FRONT_ID
1 // ID of left front motor
#define DXL_RIGHT_FRONT_ID 2 // ID of right front motor
#define BAUDRATE 1000000 // baurd rate of Dynamixel
If you use other motors than the Dynamixel XM430-W210, you might need to change other parameters in the turtlebot3_mecanum_core_motor_driver.h file as well.
The motors used in this setup are Dynamixel XM430-W210. For the use in with the rob@work mini, the default configuration of these motors needs to be changed. This can be done by using one of the ROBOTIS configuration tools, one example is the DynamixelSDK which is available from the ROBOTIS Arduino examples. There, the different example programs can be uploaded to the OpenCR board to change the configuration of the motors. It is important that during the configuration always only one motor is connected to the board. The motors need to be set to their correct ID, the ID configuration can be changed as shown in section 2. The default ID configuration is as follows:
ID | Motor |
---|---|
1 | front left |
2 | front right |
3 | rear left |
4 | rear right |
These IDs need to be set for the motors alongside the baudrate which needs to be set to 1000000. Additionally, the motors need to be set to wheel mode
. Note: some of the example files from the DynamixelSDK set the mode to joint mode
by default.
This section describes the setup for the IPA in-house developed navigation and localization software. However, the robot can be used with open source software by publishing and subscribing to the topics described in section 2. The following steps need to be taken in order to use the robot hardware with the latest IPA navigation software.
raw-mini
. If the navigation is also used the ROBOT_ENV variable needs to be set.roslaunch cob_bringup robot.launch
terminal command to start the robot. Now it should already be possible to drive the robot using the joystick.
If no navigation and localisation should be used, the setup is now finishedroslaunch ipa_navigation ipa_navigation.launch use_lts=true init_from_static_map=true
/move_base_simple/goal
topic and drive there autonomously.For automatically launching the robot on startup, the robot upstart package can be used. This needs to be installed as instruced on the documentation page. It is advised that a custom launch file is created that already contains all necessary arguments and variables such as ROBOT and ROBOT_ENV since when starting up, robot upstart uses a different user to launch the applications and cannot use the variables stored in the ~/.bashrc
file.
For debugging the motors the RoboPlus Manager 2.0 application can be used. To use this software, either the Usb2Dynamixel adapter or the OpenCR board (using this code) needs to be connected. Make sure that only one motor is connected to the board while running the initialization software.
If you have problems detecting the OpenCR board under Windows make sure that the correct drivers are installed for the STM32 chip. (more infos here)