Skip to content

Commit d5bd23c

Browse files
committed
Add custom robot configuration converted from ROS 1
Created ready-to-use configuration files for user's robot: - urdf/my_robot.urdf.xacro: Hardware config with CAN IDs 1 & 2 * rads_to_ticks: 14.323944878 * offset: 0.0 (simplified for teleop, was 3.14159265359) * delay_us: 200 * command_interface: velocity - config/my_robot_config.yaml: Controller config * wheel_separation: 0.4 m * wheel_radius: 0.12 m * publish_rate: 50 Hz * Converted to ROS 2 format (ros__parameters, wheel arrays) - launch/my_robot.launch.py: Launch file using above configs - MY_ROBOT_README.md: Quick start guide for user Configuration is ready for teleop. User can launch with: ros2 launch tinymovr_ros my_robot.launch.py
1 parent aa92dcc commit d5bd23c

4 files changed

Lines changed: 279 additions & 0 deletions

File tree

MY_ROBOT_README.md

Lines changed: 110 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,110 @@
1+
# Your Custom Robot Configuration
2+
3+
These files were automatically converted from your ROS 1 configuration for teleop use.
4+
5+
## Files Created
6+
7+
1. **`urdf/my_robot.urdf.xacro`** - Your hardware configuration
8+
- CAN IDs: wheel_1=1, wheel_2=2
9+
- Encoder conversion: 14.323944878 ticks/rad
10+
- Offsets: Set to 0.0 for teleop (you can adjust if needed)
11+
12+
2. **`config/my_robot_config.yaml`** - Your controller configuration
13+
- Wheel separation: 0.4 m
14+
- Wheel radius: 0.12 m
15+
- Publish rate: 50 Hz
16+
17+
3. **`launch/my_robot.launch.py`** - Launch file for your robot
18+
19+
## Quick Start
20+
21+
### 1. Build the package
22+
```bash
23+
cd ~/ros2_ws
24+
colcon build --packages-select tinymovr_ros
25+
source install/setup.bash
26+
```
27+
28+
### 2. Bring up CAN interface
29+
```bash
30+
sudo ip link set can0 type can bitrate 1000000
31+
sudo ip link set up can0
32+
```
33+
34+
### 3. Launch your robot
35+
```bash
36+
ros2 launch tinymovr_ros my_robot.launch.py
37+
```
38+
39+
### 4. Drive with keyboard
40+
In another terminal:
41+
```bash
42+
ros2 run teleop_twist_keyboard teleop_twist_keyboard \
43+
--ros-args --remap cmd_vel:=/cmd_vel
44+
```
45+
46+
**Controls:**
47+
- `i` - Move forward
48+
- `k` - Stop
49+
- `,` - Move backward
50+
- `j` - Turn left
51+
- `l` - Turn right
52+
- `q/z` - Increase/decrease max speeds
53+
54+
## Verify Everything Works
55+
56+
### Check joint states
57+
```bash
58+
ros2 topic echo /joint_states
59+
```
60+
You should see positions and velocities for wheel_1 and wheel_2.
61+
62+
### Check controllers
63+
```bash
64+
ros2 control list_controllers
65+
```
66+
Should show:
67+
- `joint_state_broadcaster` [active]
68+
- `diff_drive_controller` [active]
69+
70+
### Test movement
71+
```bash
72+
# Slow forward
73+
ros2 topic pub /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.1}}"
74+
75+
# Stop
76+
ros2 topic pub /cmd_vel geometry_msgs/msg/Twist "{}"
77+
```
78+
79+
## Adjustments
80+
81+
### If robot moves wrong direction
82+
Edit `urdf/my_robot.urdf.xacro` and change offset:
83+
```xml
84+
<param name="offset">3.14159265359</param> <!-- Add π for 180° flip -->
85+
```
86+
87+
### If robot turns too much/little
88+
Edit `config/my_robot_config.yaml` and adjust:
89+
```yaml
90+
wheel_separation: 0.4 # Increase to turn less, decrease to turn more
91+
```
92+
93+
### If robot moves too fast/slow
94+
Edit `config/my_robot_config.yaml` and adjust:
95+
```yaml
96+
wheel_radius: 0.12 # Increase for faster, decrease for slower
97+
```
98+
99+
## Configuration Source
100+
101+
**Converted from your ROS 1 config:**
102+
- Hardware: 2 wheels (IDs 1 & 2) with velocity control
103+
- Encoder resolution: 14.323944878 ticks/rad
104+
- Original offset: 3.14159265359 rad (set to 0.0 for teleop simplicity)
105+
- Wheel dimensions: 0.4m separation, 0.12m radius
106+
107+
## Need Help?
108+
109+
- **Documentation**: See [MIGRATION_GUIDE.md](MIGRATION_GUIDE.md) for detailed info
110+
- **Issues**: https://github.com/tinymovr/Tinymovr-ROS/issues

config/my_robot_config.yaml

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
controller_manager:
2+
ros__parameters:
3+
update_rate: 100 # Hz
4+
5+
joint_state_broadcaster:
6+
type: joint_state_broadcaster/JointStateBroadcaster
7+
8+
diff_drive_controller:
9+
type: diff_drive_controller/DiffDriveController
10+
11+
joint_state_broadcaster:
12+
ros__parameters: {}
13+
14+
diff_drive_controller:
15+
ros__parameters:
16+
# ROS 2 uses arrays for wheel names (changed from ROS 1)
17+
left_wheel_names: ["wheel_1"]
18+
right_wheel_names: ["wheel_2"]
19+
20+
# Physical parameters (from your old config)
21+
wheel_separation: 0.4
22+
wheel_radius: 0.12
23+
24+
# Fine-tuning multipliers (keep at 1.0 unless you need to adjust)
25+
wheel_separation_multiplier: 1.0
26+
left_wheel_radius_multiplier: 1.0
27+
right_wheel_radius_multiplier: 1.0
28+
29+
# Publishing and frames
30+
publish_rate: 50.0
31+
odom_frame_id: odom
32+
base_frame_id: base_link
33+
34+
# Covariance (from your old config)
35+
pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
36+
twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
37+
38+
# Control parameters
39+
open_loop: false
40+
enable_odom_tf: true
41+
cmd_vel_timeout: 0.5
42+
use_stamped_vel: false
43+
velocity_rolling_window_size: 10
44+
position_feedback: false

launch/my_robot.launch.py

Lines changed: 88 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,88 @@
1+
from launch import LaunchDescription
2+
from launch.actions import DeclareLaunchArgument, RegisterEventHandler
3+
from launch.event_handlers import OnProcessExit
4+
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration
5+
from launch_ros.actions import Node
6+
from launch_ros.substitutions import FindPackageShare
7+
8+
9+
def generate_launch_description():
10+
# Declare arguments
11+
declared_arguments = []
12+
declared_arguments.append(
13+
DeclareLaunchArgument(
14+
"use_sim_time",
15+
default_value="false",
16+
description="Use simulation (Gazebo) clock if true",
17+
)
18+
)
19+
20+
# Initialize Arguments
21+
use_sim_time = LaunchConfiguration("use_sim_time")
22+
23+
# Get URDF via xacro - using MY_ROBOT configuration
24+
robot_description_content = Command(
25+
[
26+
PathJoinSubstitution([FindExecutable(name="xacro")]),
27+
" ",
28+
PathJoinSubstitution(
29+
[FindPackageShare("tinymovr_ros"), "urdf", "my_robot.urdf.xacro"]
30+
),
31+
]
32+
)
33+
robot_description = {"robot_description": robot_description_content}
34+
35+
# Controller configuration - using MY_ROBOT configuration
36+
robot_controllers = PathJoinSubstitution(
37+
[FindPackageShare("tinymovr_ros"), "config", "my_robot_config.yaml"]
38+
)
39+
40+
# Controller manager node
41+
control_node = Node(
42+
package="controller_manager",
43+
executable="ros2_control_node",
44+
parameters=[robot_description, robot_controllers, {"use_sim_time": use_sim_time}],
45+
output="both",
46+
remappings=[
47+
("/diff_drive_controller/cmd_vel_unstamped", "/cmd_vel"),
48+
],
49+
)
50+
51+
# Robot state publisher node
52+
robot_state_pub_node = Node(
53+
package="robot_state_publisher",
54+
executable="robot_state_publisher",
55+
output="both",
56+
parameters=[robot_description, {"use_sim_time": use_sim_time}],
57+
)
58+
59+
# Joint state broadcaster spawner
60+
joint_state_broadcaster_spawner = Node(
61+
package="controller_manager",
62+
executable="spawner",
63+
arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
64+
)
65+
66+
# Diff drive controller spawner
67+
diff_drive_spawner = Node(
68+
package="controller_manager",
69+
executable="spawner",
70+
arguments=["diff_drive_controller", "--controller-manager", "/controller_manager"],
71+
)
72+
73+
# Delay start of diff_drive_controller after joint_state_broadcaster
74+
delay_diff_drive_spawner_after_joint_state_broadcaster = RegisterEventHandler(
75+
event_handler=OnProcessExit(
76+
target_action=joint_state_broadcaster_spawner,
77+
on_exit=[diff_drive_spawner],
78+
)
79+
)
80+
81+
nodes = [
82+
control_node,
83+
robot_state_pub_node,
84+
joint_state_broadcaster_spawner,
85+
delay_diff_drive_spawner_after_joint_state_broadcaster,
86+
]
87+
88+
return LaunchDescription(declared_arguments + nodes)

urdf/my_robot.urdf.xacro

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="my_robot">
3+
4+
<ros2_control name="tinymovr_system" type="system">
5+
<hardware>
6+
<plugin>tinymovr_ros/TinymovrSystem</plugin>
7+
<param name="can_interface">can0</param>
8+
</hardware>
9+
10+
<!-- WHEEL 1 (LEFT) -->
11+
<joint name="wheel_1">
12+
<command_interface name="velocity"/>
13+
<state_interface name="position"/>
14+
<state_interface name="velocity"/>
15+
<state_interface name="effort"/>
16+
<param name="id">1</param>
17+
<param name="delay_us">200</param>
18+
<param name="rads_to_ticks">14.323944878</param>
19+
<param name="command_interface">velocity</param>
20+
<param name="offset">0.0</param> <!-- Set to 0.0 for teleop (was 3.14159265359) -->
21+
</joint>
22+
23+
<!-- WHEEL 2 (RIGHT) -->
24+
<joint name="wheel_2">
25+
<command_interface name="velocity"/>
26+
<state_interface name="position"/>
27+
<state_interface name="velocity"/>
28+
<state_interface name="effort"/>
29+
<param name="id">2</param>
30+
<param name="delay_us">200</param>
31+
<param name="rads_to_ticks">14.323944878</param>
32+
<param name="command_interface">velocity</param>
33+
<param name="offset">0.0</param> <!-- Set to 0.0 for teleop (was 3.14159265359) -->
34+
</joint>
35+
</ros2_control>
36+
37+
</robot>

0 commit comments

Comments
 (0)