Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add ZED urdf + list of choices #49

Merged
merged 15 commits into from
Nov 13, 2023
3 changes: 2 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,5 @@ dev_utils/
build/
install/
log/
__pycache__/
__pycache__/
.pre-commit-config.yaml
23 changes: 10 additions & 13 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ ROS2 packages for ROSbot XL

### `rosbot_xl`

Metapackeage that contains dependencies to other repositories. It is also used to define whether simulation dependencies should be used.
Metapackeage that contains dependencies to other repositories. It is also used to define whether simulation dependencies should be used.

### `rosbot_xl_bringup`

Expand Down Expand Up @@ -42,17 +42,15 @@ To run the software on real ROSbot XL, also communication with Digital Board wil
First update your firmware to make sure that you use the latest version, then run the `micro-ROS` agent.
For detailed instructions refer to the [rosbot_xl_firmware repository](https://github.com/husarion/rosbot_xl_firmware).

## Source build
## Prepare environment

### Prerequisites

Install `colcon`, `vsc` and `rosdep`:
1. **Install `colcon`, `vsc` and `rosdep`**
```
sudo apt-get update
sudo apt-get install -y python3-colcon-common-extensions python3-vcstool python3-rosdep
```

Create workspace folder and clone `rosbot_xl_ros` repository:
2. **Create workspace folder and clone `rosbot_xl_ros` repository:**
```
mkdir -p ros2_ws/src
cd ros2_ws
Expand All @@ -61,7 +59,7 @@ git clone https://github.com/husarion/rosbot_xl_ros src/

### Build and run on hardware

Building:
1. **Building**
```
export HUSARION_ROS_BUILD=hardware

Expand All @@ -77,19 +75,18 @@ rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y
colcon build
```

> **Prerequisites**
>
> Before starting the software on the robot please make sure that you're using the latest firmware and run the `micro-ROS` agent (as described in the *Usage on hardware* step).
> [!NOTE]
> Before starting the software on the robot please make sure that you're using the latest firmware and run the `micro-ROS` agent as described in the [Usage on hardware](#usage-on-hardware) step.

Running:
2. **Running**
```
source install/setup.bash
ros2 launch rosbot_xl_bringup bringup.launch.py
```

### Build and run Gazebo simulation

Building:
1. **Building**
```
export HUSARION_ROS_BUILD=simulation

Expand All @@ -104,7 +101,7 @@ rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y
colcon build
```

Running:
2. **Running**
```
source install/setup.bash
ros2 launch rosbot_xl_gazebo simulation.launch.py
Expand Down
6 changes: 3 additions & 3 deletions rosbot_xl_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,14 @@ def generate_launch_description():
declare_lidar_model_arg = DeclareLaunchArgument(
"lidar_model",
default_value="slamtec_rplidar_s1",
description="Lidar model added to the URDF",
description="Add LiDAR model to the robot URDF",
)

camera_model = LaunchConfiguration("camera_model")
declare_camera_model_arg = DeclareLaunchArgument(
"camera_model",
default_value="None",
description="Camera model added to the URDF",
description="Add camera model to the robot URDF",
)

include_camera_mount = LaunchConfiguration("include_camera_mount")
Expand Down Expand Up @@ -115,4 +115,4 @@ def generate_launch_description():
laser_filter_node,
]

return LaunchDescription(actions)
return LaunchDescription(actions)
23 changes: 20 additions & 3 deletions rosbot_xl_controller/launch/controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,14 +43,31 @@ def generate_launch_description():
declare_lidar_model_arg = DeclareLaunchArgument(
"lidar_model",
default_value="slamtec_rplidar_s1",
description="Lidar model added to the URDF",
description="Add LiDAR model to the robot URDF",
choices=[
"None",
"slamtec_rplidar_s1",
"slamtec_rplidar_a2",
"slamtec_rplidar_a3",
"velodyne_puck",
],
)

camera_model = LaunchConfiguration("camera_model")
declare_camera_model_arg = DeclareLaunchArgument(
"camera_model",
default_value="None",
description="Camera model added to the URDF",
description="Add camera model to the robot URDF",
rafal-gorecki marked this conversation as resolved.
Show resolved Hide resolved
choices=[
"None",
"intel_realsense_d435",
"stereolabs_zed",
"stereolabs_zedm",
"stereolabs_zed2",
"stereolabs_zed2i",
"stereolabs_zedx",
"stereolabs_zedxm",
],
)

include_camera_mount = LaunchConfiguration("include_camera_mount")
Expand Down Expand Up @@ -218,4 +235,4 @@ def generate_launch_description():
delay_imu_broadcaster_spawner_after_robot_controller_spawner,
]

return LaunchDescription(actions)
return LaunchDescription(actions)
44 changes: 39 additions & 5 deletions rosbot_xl_description/urdf/rosbot_xl.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<xacro:arg name="mecanum" default="false" />
<xacro:arg name="lidar_model" default="slamtec_rplidar_s1" />
<xacro:arg name="camera_model" default="None" />
<xacro:arg name="camera_model" default="stereolabs_zed2" />
<xacro:arg name="include_camera_mount" default="false" />
<xacro:arg name="use_sim" default="false" />
<xacro:arg name="simulation_engine" default="ignition-gazebo" />
Expand All @@ -28,7 +28,7 @@

<xacro:property name="lidar_model" value="$(arg lidar_model)" />
<xacro:property name="lidar_parent_link" value="cover_link" />
<xacro:property name="lidar_xyz" value="0.0 0.0 0.0" />
<xacro:property name="lidar_xyz" value="0.02 0.0 0.0" />
<xacro:property name="lidar_rpy" value="0.0 0.0 0.0" />
<xacro:property name="lidar_use_gpu" value="true" />
<!-- use_gpu has to be set to true, CPU lidar doesn't work in ignition -
Expand Down Expand Up @@ -102,10 +102,44 @@
simulation_engine="$(arg simulation_engine)" />
</xacro:if>

<!-- INCLUDE CAMERA MOUNT -->
<xacro:if value="${camera_model.startswith('stereolabs')}">
<xacro:if value="${camera_model == 'stereolabs_zed'}">
<xacro:property name="camera_model_type" value="zed" />
</xacro:if>
<xacro:if value="${camera_model == 'stereolabs_zedm'}">
<xacro:property name="camera_model_type" value="zedm" />
</xacro:if>
<xacro:if value="${camera_model == 'stereolabs_zed2'}">
<xacro:property name="camera_model_type" value="zed2" />
</xacro:if>
<xacro:if value="${camera_model == 'stereolabs_zed2i'}">
<xacro:property name="camera_model_type" value="zed2i" />
</xacro:if>
<xacro:if value="${camera_model == 'stereolabs_zedx'}">
<xacro:property name="camera_model_type" value="zedx" />
</xacro:if>
<xacro:if value="${camera_model == 'stereolabs_zedxm'}">
<xacro:property name="camera_model_type" value="zedxm" />
</xacro:if>

<xacro:include
filename="$(find ros_components_description)/urdf/stereolabs_zed.urdf.xacro"
ns="camera" />
<xacro:camera.zed_camera
parent_link="${camera_parent_link}"
xyz="${camera_xyz}"
rpy="${camera_rpy}"
model="${camera_model_type}"
name="camera"
topic="camera"
use_nominal_extrinsics="$(arg use_sim)"
simulation_engine="$(arg simulation_engine)" />
</xacro:if>

<!-- INCLUDE CAMERA MOUNT - add if camera_model is not empty -->

<xacro:property name="include_camera_mount" value="$(arg include_camera_mount)" />
<xacro:if value="${include_camera_mount or camera_model == 'intel_realsense_d435'}">
<xacro:if value="${include_camera_mount or camera_model != ''}">
rafal-gorecki marked this conversation as resolved.
Show resolved Hide resolved
<xacro:include filename="$(find rosbot_xl_description)/urdf/components/camera_mount.urdf.xacro"
ns="camera_mount" />
<xacro:camera_mount.camera_mount
Expand All @@ -116,4 +150,4 @@
camera_mount_angle_2="0.0" />
</xacro:if>

</robot>
</robot>
32 changes: 11 additions & 21 deletions rosbot_xl_gazebo/launch/simulation.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,14 +28,14 @@ def generate_launch_description():
declare_lidar_model_arg = DeclareLaunchArgument(
"lidar_model",
default_value="slamtec_rplidar_s1",
description="Lidar model added to the URDF",
description="Add LiDAR model to the robot URDF",
)

camera_model = LaunchConfiguration("camera_model")
declare_camera_model_arg = DeclareLaunchArgument(
"camera_model",
default_value="None",
description="Camera model added to the URDF",
default_value="intel_realsense_d435",
description="Add camera model to the robot URDF model",
)

include_camera_mount = LaunchConfiguration("include_camera_mount")
Expand Down Expand Up @@ -89,24 +89,14 @@ def generate_launch_description():
executable="parameter_bridge",
name="ign_bridge",
arguments=[
"/clock" + "@rosgraph_msgs/msg/Clock" + "[ignition.msgs.Clock",
"/scan" + "@sensor_msgs/msg/LaserScan" + "[ignition.msgs.LaserScan",
"/velodyne_points/points"
+ "@sensor_msgs/msg/PointCloud2"
+ "[ignition.msgs.PointCloudPacked",
"/camera/color/camera_info"
+ "@sensor_msgs/msg/CameraInfo"
+ "[ignition.msgs.CameraInfo",
"/camera/color/image_raw"
+ "@sensor_msgs/msg/Image"
+ "[ignition.msgs.Image",
"/camera/camera_info"
+ "@sensor_msgs/msg/CameraInfo"
+ "[ignition.msgs.CameraInfo",
"/camera/depth" + "@sensor_msgs/msg/Image" + "[ignition.msgs.Image",
"/camera/depth/points"
+ "@sensor_msgs/msg/PointCloud2"
+ "[ignition.msgs.PointCloudPacked",
"/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock",
rafal-gorecki marked this conversation as resolved.
Show resolved Hide resolved
"/scan@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/velodyne_points/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked",
"/camera/color/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"/camera/color/image_raw@sensor_msgs/msg/Image[ignition.msgs.Image",
"/camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"/camera/depth@sensor_msgs/msg/Image[ignition.msgs.Image",
"/camera/depth/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked",
],
remappings=[
("/velodyne_points/points", "/velodyne_points"),
Expand Down