Add ros2 launch and make it the default
This commit is contained in:
+2
-1
@@ -25,6 +25,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \
|
|||||||
ros-${ROS_DISTRO}-geometry-msgs \
|
ros-${ROS_DISTRO}-geometry-msgs \
|
||||||
ros-${ROS_DISTRO}-std-msgs \
|
ros-${ROS_DISTRO}-std-msgs \
|
||||||
ros-${ROS_DISTRO}-sensor-msgs \
|
ros-${ROS_DISTRO}-sensor-msgs \
|
||||||
|
ros-${ROS_DISTRO}-launch-ros \
|
||||||
python3-smbus \
|
python3-smbus \
|
||||||
&& rm -rf /var/lib/apt/lists/*
|
&& rm -rf /var/lib/apt/lists/*
|
||||||
|
|
||||||
@@ -42,4 +43,4 @@ COPY docker-entrypoint.sh /docker-entrypoint.sh
|
|||||||
RUN chmod +x /docker-entrypoint.sh
|
RUN chmod +x /docker-entrypoint.sh
|
||||||
|
|
||||||
ENTRYPOINT ["/docker-entrypoint.sh"]
|
ENTRYPOINT ["/docker-entrypoint.sh"]
|
||||||
CMD ["ros2", "run", "my_robot", "motor_controller"]
|
CMD ["ros2", "launch", "my_robot", "robot.launch.py"]
|
||||||
|
|||||||
@@ -165,7 +165,7 @@ Replace `matt` with the username configured in [ansible/inventory.ini](ansible/i
|
|||||||
|
|
||||||
## Launching
|
## Launching
|
||||||
|
|
||||||
The container needs access to the I²C bus that the motor controller is wired to. Pass only that device rather than running the container in privileged mode:
|
The default `CMD` starts both nodes together via the launch file. The container needs access to the I²C bus — pass only that device rather than running privileged:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
docker run --rm \
|
docker run --rm \
|
||||||
@@ -175,11 +175,11 @@ docker run --rm \
|
|||||||
my_robot:latest
|
my_robot:latest
|
||||||
```
|
```
|
||||||
|
|
||||||
If your board exposes the motor controller on a different bus (check with `ls /dev/i2c-*` on the host), substitute the correct device node (e.g. `--device /dev/i2c-0`).
|
If your board exposes the controller on a different bus (check with `ls /dev/i2c-*` on the host), substitute the correct device node (e.g. `--device /dev/i2c-0`).
|
||||||
|
|
||||||
### Camera orientation node
|
### Overriding parameters at launch
|
||||||
|
|
||||||
Override the default `CMD` to run the camera orientation node instead:
|
Launch arguments can be appended after the image name:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
docker run --rm \
|
docker run --rm \
|
||||||
@@ -187,63 +187,22 @@ docker run --rm \
|
|||||||
--device /dev/i2c-1 \
|
--device /dev/i2c-1 \
|
||||||
--env ROS_DOMAIN_ID=0 \
|
--env ROS_DOMAIN_ID=0 \
|
||||||
my_robot:latest \
|
my_robot:latest \
|
||||||
ros2 run my_robot camera_orientation
|
ros2 launch my_robot robot.launch.py \
|
||||||
|
wheel_base:=0.25 max_speed:=0.8 tilt_center_deg:=45.0
|
||||||
```
|
```
|
||||||
|
|
||||||
#### Overriding parameters at launch
|
Available launch arguments:
|
||||||
|
|
||||||
```bash
|
| Argument | Default | Description |
|
||||||
docker run --rm \
|
|---|---|---|
|
||||||
--network=host \
|
| `wheel_base` | `0.3` | Distance between left and right wheels (m) |
|
||||||
--device /dev/i2c-1 \
|
| `max_speed` | `1.0` | Maximum motor speed in library units |
|
||||||
--env ROS_DOMAIN_ID=0 \
|
| `pan_center_deg` | `90.0` | Pan angle at startup and shutdown (degrees) |
|
||||||
my_robot:latest \
|
| `tilt_center_deg` | `60.0` | Tilt angle at startup and shutdown (degrees) |
|
||||||
ros2 run my_robot camera_orientation \
|
|
||||||
--ros-args -p pan_center_deg:=90.0 -p tilt_center_deg:=45.0
|
|
||||||
```
|
|
||||||
|
|
||||||
#### Commanding the camera from the host
|
|
||||||
|
|
||||||
Pan to centre (90°) and tilt to 30°:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
ros2 topic pub --once /joint_command sensor_msgs/msg/JointState \
|
|
||||||
"{name: ['pan', 'tilt'], position: [1.5708, 0.5236]}"
|
|
||||||
```
|
|
||||||
|
|
||||||
You can command a single axis by omitting the other joint name:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
# Pan only
|
|
||||||
ros2 topic pub --once /joint_command sensor_msgs/msg/JointState \
|
|
||||||
"{name: ['pan'], position: [0.0]}"
|
|
||||||
```
|
|
||||||
|
|
||||||
#### Verifying orientation state
|
|
||||||
|
|
||||||
```bash
|
|
||||||
ros2 topic echo /joint_states
|
|
||||||
```
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### Overriding parameters at launch (motor controller)
|
|
||||||
|
|
||||||
ROS 2 parameters can be passed through `--ros-args`:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
docker run --rm \
|
|
||||||
--network=host \
|
|
||||||
--device /dev/i2c-1 \
|
|
||||||
--env ROS_DOMAIN_ID=0 \
|
|
||||||
my_robot:latest \
|
|
||||||
ros2 run my_robot motor_controller \
|
|
||||||
--ros-args -p wheel_base:=0.25 -p max_speed:=0.8
|
|
||||||
```
|
|
||||||
|
|
||||||
### Sending velocity commands from the host
|
### Sending velocity commands from the host
|
||||||
|
|
||||||
With the container running, publish a `cmd_vel` message from another terminal (requires ROS 2 installed on the host or a second container on the same network):
|
With the container running, publish from another terminal (requires ROS 2 on the host or a second container on the same network):
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
# Drive forward at 0.2 m/s
|
# Drive forward at 0.2 m/s
|
||||||
@@ -259,10 +218,31 @@ ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist \
|
|||||||
"{linear: {x: 0.0}, angular: {z: 0.0}}"
|
"{linear: {x: 0.0}, angular: {z: 0.0}}"
|
||||||
```
|
```
|
||||||
|
|
||||||
|
### Commanding the camera from the host
|
||||||
|
|
||||||
|
Pan to centre (90°) and tilt to 30°:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
ros2 topic pub --once /joint_command sensor_msgs/msg/JointState \
|
||||||
|
"{name: ['pan', 'tilt'], position: [1.5708, 0.5236]}"
|
||||||
|
```
|
||||||
|
|
||||||
|
A single axis can be commanded by omitting the other joint name:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
# Pan only
|
||||||
|
ros2 topic pub --once /joint_command sensor_msgs/msg/JointState \
|
||||||
|
"{name: ['pan'], position: [0.0]}"
|
||||||
|
```
|
||||||
|
|
||||||
### Verifying telemetry
|
### Verifying telemetry
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
|
# Wheel speeds
|
||||||
ros2 topic echo /current_wheel_speeds
|
ros2 topic echo /current_wheel_speeds
|
||||||
|
|
||||||
|
# Camera orientation
|
||||||
|
ros2 topic echo /joint_states
|
||||||
```
|
```
|
||||||
|
|
||||||
---
|
---
|
||||||
@@ -277,6 +257,8 @@ ros2 topic echo /current_wheel_speeds
|
|||||||
│ └── my_robot/
|
│ └── my_robot/
|
||||||
│ ├── package.xml # ROS package manifest
|
│ ├── package.xml # ROS package manifest
|
||||||
│ ├── setup.py # ament_python build definition
|
│ ├── setup.py # ament_python build definition
|
||||||
|
│ ├── launch/
|
||||||
|
│ │ └── robot.launch.py # Starts both nodes together
|
||||||
│ └── my_robot/
|
│ └── my_robot/
|
||||||
│ ├── __init__.py
|
│ ├── __init__.py
|
||||||
│ ├── motor_controller_node.py # Differential-drive motor control
|
│ ├── motor_controller_node.py # Differential-drive motor control
|
||||||
|
|||||||
@@ -0,0 +1,45 @@
|
|||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
return LaunchDescription([
|
||||||
|
|
||||||
|
# ── Motor controller arguments ────────────────────────────────────
|
||||||
|
DeclareLaunchArgument('wheel_base', default_value='0.3',
|
||||||
|
description='Distance between left and right wheels (m)'),
|
||||||
|
DeclareLaunchArgument('max_speed', default_value='1.0',
|
||||||
|
description='Maximum motor speed in library units'),
|
||||||
|
|
||||||
|
# ── Camera orientation arguments ──────────────────────────────────
|
||||||
|
DeclareLaunchArgument('pan_center_deg', default_value='90.0',
|
||||||
|
description='Pan angle at startup and shutdown (degrees)'),
|
||||||
|
DeclareLaunchArgument('tilt_center_deg', default_value='60.0',
|
||||||
|
description='Tilt angle at startup and shutdown (degrees)'),
|
||||||
|
|
||||||
|
# ── Nodes ─────────────────────────────────────────────────────────
|
||||||
|
Node(
|
||||||
|
package='my_robot',
|
||||||
|
executable='motor_controller',
|
||||||
|
name='motor_controller',
|
||||||
|
parameters=[{
|
||||||
|
'wheel_base': LaunchConfiguration('wheel_base'),
|
||||||
|
'max_speed': LaunchConfiguration('max_speed'),
|
||||||
|
}],
|
||||||
|
output='screen',
|
||||||
|
),
|
||||||
|
|
||||||
|
Node(
|
||||||
|
package='my_robot',
|
||||||
|
executable='camera_orientation',
|
||||||
|
name='camera_orientation',
|
||||||
|
parameters=[{
|
||||||
|
'pan_center_deg': LaunchConfiguration('pan_center_deg'),
|
||||||
|
'tilt_center_deg': LaunchConfiguration('tilt_center_deg'),
|
||||||
|
}],
|
||||||
|
output='screen',
|
||||||
|
),
|
||||||
|
|
||||||
|
])
|
||||||
@@ -10,6 +10,8 @@
|
|||||||
<exec_depend>geometry_msgs</exec_depend>
|
<exec_depend>geometry_msgs</exec_depend>
|
||||||
<exec_depend>std_msgs</exec_depend>
|
<exec_depend>std_msgs</exec_depend>
|
||||||
<exec_depend>sensor_msgs</exec_depend>
|
<exec_depend>sensor_msgs</exec_depend>
|
||||||
|
<exec_depend>launch</exec_depend>
|
||||||
|
<exec_depend>launch_ros</exec_depend>
|
||||||
|
|
||||||
<buildtool_depend>ament_python</buildtool_depend>
|
<buildtool_depend>ament_python</buildtool_depend>
|
||||||
|
|
||||||
|
|||||||
@@ -9,6 +9,7 @@ setup(
|
|||||||
data_files=[
|
data_files=[
|
||||||
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
|
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
|
||||||
('share/' + package_name, ['package.xml']),
|
('share/' + package_name, ['package.xml']),
|
||||||
|
('share/' + package_name + '/launch', ['launch/robot.launch.py']),
|
||||||
],
|
],
|
||||||
install_requires=['setuptools'],
|
install_requires=['setuptools'],
|
||||||
zip_safe=True,
|
zip_safe=True,
|
||||||
|
|||||||
Reference in New Issue
Block a user