Skip to content

Commit

Permalink
Matches convention with cmd_vel and odom topics.
Browse files Browse the repository at this point in the history
Signed-off-by: Franco Cipollone <[email protected]>
  • Loading branch information
francocipollone committed Feb 13, 2024
1 parent 63320e0 commit a5ec243
Show file tree
Hide file tree
Showing 8 changed files with 36 additions and 20 deletions.
31 changes: 26 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -123,17 +123,38 @@ By default sensors like the camera and the lidar are initialized. This can be di
- include_rplidar: `true` as default.
- include_camera: `true` as default.

After the robot is launched, use `ROS 2 CLI` for inspecting environment. E.g: By doing `ros2 topic list` the available topics can be displayed.
After the robot is launched, use `ROS 2 CLI` for inspecting environment.
For example, by doing `ros2 topic list` the available topics can be displayed:

/camera_info
/cmd_vel
/image_raw
/odom
/robot_description
/scan
/tf
/tf_static

_Note: Showing just some of them_

### Teleoperation

Launch files for using the keyboard or a joystick for teleoperating the robot are provided.

[`twist_mux`](http://wiki.ros.org/twist_mux) is used to at the same time accept command velocities from different topics using certain priority for each one of them (See [twist_mux config](andino_bringup/config/twist_mux.yaml)). Available topics are (ordering by priority):
#### Keyboard

```
ros2 launch andino_bringup teleop_keyboard.launch.py
```
This is similarly to just call `ros2 run teleop_twist_keyboard teleop_twist_keyboard`

#### Joystick

- cmd_vel
- cmd_vel_keyboard
- cmd_vel_joy
Using a joystick for teleoperating is notably better.
You need the joystick configured as explained [here](andino_hardware/README.md#Using-joystick-for-teleoperation)
```
ros2 launch andino_bringup teleop_joystick.launch.py
```

### RViz

Expand Down
9 changes: 0 additions & 9 deletions andino_bringup/launch/andino_robot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,20 +103,11 @@ def generate_launch_description():
rplidar_timer = TimerAction(period=3.0, actions=[include_rplidar])
camera_timer = TimerAction(period=3.0, actions=[include_camera])

twist_mux_params = os.path.join(pkg_andino_bringup,'config','twist_mux.yaml')
twist_mux = Node(
package="twist_mux",
executable="twist_mux",
parameters=[twist_mux_params],
remappings=[('/cmd_vel_out','/diff_controller/cmd_vel_unstamped')]
)

return LaunchDescription([
include_andino_description,
andino_control_timer,
camera_arg,
camera_timer,
rplidar_arg,
rplidar_timer,
twist_mux,
])
2 changes: 1 addition & 1 deletion andino_bringup/launch/teleop_joystick.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ def generate_launch_description():

cmd_vel_topic_arg = DeclareLaunchArgument(
'cmd_vel_topic',
default_value='/cmd_vel_joy',
default_value='/cmd_vel',
description='Indicates the cmd_vel topic.')
cmd_vel_topic = LaunchConfiguration('cmd_vel_topic')

Expand Down
1 change: 0 additions & 1 deletion andino_bringup/launch/teleop_keyboard.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@ def generate_launch_description():
package='teleop_twist_keyboard',
executable='teleop_twist_keyboard',
name='teleop_twist_keyboard_node',
remappings=[('/cmd_vel','/cmd_vel_keyboard')],
output='screen',
prefix = 'xterm -e',
)
Expand Down
1 change: 0 additions & 1 deletion andino_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
<exec_depend>rplidar_ros</exec_depend>
<exec_depend>teleop_twist_joy</exec_depend>
<exec_depend>joy_linux</exec_depend>
<exec_depend>twist_mux</exec_depend>
<exec_depend>v4l2_camera</exec_depend>
<exec_depend>laser_filters</exec_depend>
<exec_depend>rosbag2_storage_mcap</exec_depend>
Expand Down
4 changes: 2 additions & 2 deletions andino_control/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ flowchart TD
M(Controller Manager) -..-> |manages lifecycle| C
M(Controller Manager) -..-> |activates hw component| B
D["/diff_controller/cmd_vel"] -->|subs| A
A -->|pubs| O["/diff_controller/odom"]
D["/cmd_vel"] -->|subs| A
A -->|pubs| O["/odom"]
A -->|pubs| T["/tf"]
C -->|pubs| J["/joint_states"]
Expand Down
1 change: 1 addition & 0 deletions andino_control/config/andino_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ controller_manager:

diff_controller:
ros__parameters:
# See https://github.com/ros-controls/ros2_controllers/blob/humble/diff_drive_controller/src/diff_drive_controller_parameter.yaml
publish_rate: 50.0
left_wheel_names: ['left_wheel_joint']
right_wheel_names: ['right_wheel_joint']
Expand Down
7 changes: 6 additions & 1 deletion andino_control/launch/andino_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,12 @@ def generate_launch_description():
executable="ros2_control_node",
parameters=[{'robot_description': ParameterValue(robot_description, value_type=str)},
controller_params_file],

remappings=[
('/diff_controller/cmd_vel', '/cmd_vel'), # Used use_stamped_vel param is true
('/diff_controller/cmd_vel_unstamped', '/cmd_vel'), # Used if use_stamped_vel param is false
('/diff_controller/cmd_vel_out', '/cmd_vel_out'), # Used if publish_limited_velocity param is true
('/diff_controller/odom', '/odom'),
],
output="both",
)

Expand Down

0 comments on commit a5ec243

Please sign in to comment.