Skip to content

Commit

Permalink
Simplify prefix
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Nov 15, 2023
1 parent 86c7588 commit 8cf5bda
Show file tree
Hide file tree
Showing 10 changed files with 76 additions and 107 deletions.
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ repos:
args: [--pytest-test-first]

- repo: https://github.com/codespell-project/codespell
rev: v1.16.0
rev: v2.2.6
hooks:
- id: codespell
name: codespell
Expand All @@ -26,13 +26,13 @@ repos:
types: [text]

- repo: https://github.com/jumanjihouse/pre-commit-hook-yamlfmt
rev: 0.2.1
rev: 0.2.3
hooks:
- id: yamlfmt
files: ^.github|./\.yaml

- repo: https://github.com/psf/black
rev: 23.10.1
rev: 23.11.0
hooks:
- id: black
args: ["--line-length=99", "--experimental-string-processing"]
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ black rosbot*
```

## Demo
Bellow you can find demos with ROSbots:
Below you can find demos with ROSbots:
- in [rosbot-docker](https://github.com/husarion/rosbot-docker/tree/ros2) you will find a simple example how to drive ROSbot with `teleop_twist_keyboard`.
- in [rosbot-sensors](https://github.com/husarion/rosbot-sensors) you will find an example how to visualize all ROSbot sensors.
- in [rosbot-mapping](https://github.com/husarion/rosbot-mapping) you will find an example how to use ROSbot with the [slam_toolbox](https://github.com/SteveMacenski/slam_toolbox/).
Expand Down
2 changes: 0 additions & 2 deletions rosbot_bringup/config/ekf.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
publish_tf: true
publish_acceleration: false

# The odometry topic name is overwritten in launch file due to the namespace argument
odom0: rosbot_base_controller/odom
odom0_config: [false, false, false, # X , Y , Z
false, false, false, # roll , pitch ,yaw
Expand All @@ -31,7 +30,6 @@
odom0_differential: false
odom0_relative: true

# The IMU topic name is overwritten in launch file due to the namespace argument
imu0: imu_broadcaster/imu
imu0_config: [false, false, false, # X , Y , Z
false, false, true, # roll , pitch ,yaw
Expand Down
7 changes: 1 addition & 6 deletions rosbot_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
def generate_launch_description():
namespace = LaunchConfiguration("namespace")
namespace_tf_prefix = PythonExpression(
["''", " if '", namespace, "' == '' ", "else ", "'", namespace, "_'"]
["'' if '", namespace, "' == '' else '", namespace, "_'"]
)
declare_namespace_arg = DeclareLaunchArgument(
"namespace",
Expand Down Expand Up @@ -93,11 +93,6 @@ def generate_launch_description():
output="screen",
parameters=[
ekf_config,
{
"map_frame": LaunchConfiguration(
"ekf_map_frame", default=[namespace_tf_prefix, "map"]
)
},
{
"odom_frame": LaunchConfiguration(
"ekf_odom_frame", default=[namespace_tf_prefix, "odom"]
Expand Down
2 changes: 1 addition & 1 deletion rosbot_controller/launch/controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ def generate_launch_description():
use_gpu,
" simulation_engine:=",
simulation_engine,
" tf_prefix:=",
" namespace:=",
namespace,
]
)
Expand Down
53 changes: 23 additions & 30 deletions rosbot_description/urdf/body.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,22 +4,15 @@
<xacro:macro name="body" params="wheel_radius mecanum use_gpu tf_prefix">
<xacro:include filename="$(find rosbot_description)/urdf/components/vl53lox.urdf.xacro" ns="range_sensor" />

<xacro:if value="${tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="" />
</xacro:if>
<xacro:unless value="${tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="${tf_prefix}_" />
</xacro:unless>
<link name="${tf_prefix}base_link" />

<link name="${tf_prefix_ext}base_link" />

<joint name="${tf_prefix_ext}base_to_${tf_prefix_ext}body_joint" type="fixed">
<joint name="${tf_prefix}base_to_${tf_prefix}body_joint" type="fixed">
<origin xyz="0.0 0.0 ${wheel_radius}" rpy="0.0 0.0 0.0" />
<parent link="${tf_prefix_ext}base_link" />
<child link="${tf_prefix_ext}body_link" />
<parent link="${tf_prefix}base_link" />
<child link="${tf_prefix}body_link" />
</joint>

<link name="${tf_prefix_ext}body_link">
<link name="${tf_prefix}body_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_description)/meshes/body.stl" scale="0.001 0.001 0.001" />
Expand All @@ -45,17 +38,17 @@
<origin xyz="0.0 0.0 ${0.040 - 0.02}" rpy="0.0 0.0 0.0" />
</inertial>
</link>
<gazebo reference="${tf_prefix_ext}body_link">
<gazebo reference="${tf_prefix}body_link">
<material>Gazebo/White</material>
</gazebo>

<joint name="${tf_prefix_ext}body_to_${tf_prefix_ext}cover_joint" type="fixed">
<joint name="${tf_prefix}body_to_${tf_prefix}cover_joint" type="fixed">
<origin xyz="0.0 0.0 0.0603" rpy="0.0 0.0 0.0" />
<parent link="${tf_prefix_ext}body_link" />
<child link="${tf_prefix_ext}cover_link" />
<parent link="${tf_prefix}body_link" />
<child link="${tf_prefix}cover_link" />
</joint>

<link name="${tf_prefix_ext}cover_link">
<link name="${tf_prefix}cover_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_description)/meshes/cover.stl" scale="0.001 0.001 0.001" />
Expand All @@ -65,31 +58,31 @@
<color rgba="0.8 0.0 0.0 1.0" />
</material>
</visual>
<gazebo reference="${tf_prefix_ext}cover_link">
<gazebo reference="${tf_prefix}cover_link">
<material>Gazebo/Red</material>
</gazebo>
</link>

<joint name="${tf_prefix_ext}body_to_${tf_prefix_ext}imu_joint" type="fixed">
<joint name="${tf_prefix}body_to_${tf_prefix}imu_joint" type="fixed">
<origin xyz="0.003 -0.0495 0.04332" rpy="0.0 0.0 0.0" />
<parent link="${tf_prefix_ext}body_link" />
<child link="${tf_prefix_ext}imu_link" />
<parent link="${tf_prefix}body_link" />
<child link="${tf_prefix}imu_link" />
</joint>

<link name="${tf_prefix_ext}imu_link" />
<link name="${tf_prefix}imu_link" />

<joint name="${tf_prefix_ext}body_to_${tf_prefix_ext}camera_joint" type="fixed">
<joint name="${tf_prefix}body_to_${tf_prefix}camera_joint" type="fixed">
<origin xyz="-0.0141 0.0 0.125" rpy="0.0 0.0 0.0" />
<parent link="${tf_prefix_ext}body_link" />
<child link="${tf_prefix_ext}camera_link" />
<parent link="${tf_prefix}body_link" />
<child link="${tf_prefix}camera_link" />
</joint>

<link name="${tf_prefix_ext}camera_link" />
<link name="${tf_prefix}camera_link" />

<xacro:range_sensor.vl53lox parent="${tf_prefix_ext}body_link" xyz="0.0926 0.05 0.015" rpy="0.0 0.0 ${radians(12.5)}" side="fl" tf_prefix="${tf_prefix}" />
<xacro:range_sensor.vl53lox parent="${tf_prefix_ext}body_link" xyz="0.0926 -0.05 0.015" rpy="0.0 0.0 ${radians(-12.5)}" side="fr" tf_prefix="${tf_prefix}" />
<xacro:range_sensor.vl53lox parent="${tf_prefix_ext}body_link" xyz="-0.0926 0.05 0.0115" rpy="0.0 0.0 ${radians(167.5)}" side="rl" tf_prefix="${tf_prefix}" />
<xacro:range_sensor.vl53lox parent="${tf_prefix_ext}body_link" xyz="-0.0926 -0.05 0.0115" rpy="0.0 0.0 ${radians(192.5)}" side="rr" tf_prefix="${tf_prefix}" />
<xacro:range_sensor.vl53lox parent="${tf_prefix}body_link" xyz="0.0926 0.05 0.015" rpy="0.0 0.0 ${radians(12.5)}" side="fl" tf_prefix="${tf_prefix}" />
<xacro:range_sensor.vl53lox parent="${tf_prefix}body_link" xyz="0.0926 -0.05 0.015" rpy="0.0 0.0 ${radians(-12.5)}" side="fr" tf_prefix="${tf_prefix}" />
<xacro:range_sensor.vl53lox parent="${tf_prefix}body_link" xyz="-0.0926 0.05 0.0115" rpy="0.0 0.0 ${radians(167.5)}" side="rl" tf_prefix="${tf_prefix}" />
<xacro:range_sensor.vl53lox parent="${tf_prefix}body_link" xyz="-0.0926 -0.05 0.0115" rpy="0.0 0.0 ${radians(192.5)}" side="rr" tf_prefix="${tf_prefix}" />

</xacro:macro>
</robot>
21 changes: 7 additions & 14 deletions rosbot_description/urdf/components/vl53lox.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,30 +3,23 @@
<!-- vl53lox defining macro -->
<xacro:macro name="vl53lox" params="parent xyz rpy side tf_prefix">

<xacro:if value="${tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="" />
</xacro:if>
<xacro:unless value="${tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="${tf_prefix}_" />
</xacro:unless>

<joint name="${parent.rstrip('_link')}_${tf_prefix_ext}${side}_range_joint" type="fixed">
<joint name="${parent.rstrip('_link')}_${tf_prefix}${side}_range_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent}" />
<child link="${tf_prefix_ext}${side}_range" />
<child link="${tf_prefix}${side}_range" />
</joint>

<link name="${tf_prefix_ext}${side}_range" />
<link name="${tf_prefix}${side}_range" />

<!-- an IR sensor or a sonar are not implemented yet
https://github.com/gazebosim/gz-sensors/issues/19 -->
<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<gazebo reference="${tf_prefix_ext}${side}_range">
<sensor name="${tf_prefix_ext}${side}_range" type='gpu_lidar'>
<gazebo reference="${tf_prefix}${side}_range">
<sensor name="${tf_prefix}${side}_range" type='gpu_lidar'>

<topic>/range/${side}</topic>
<frame_id>${tf_prefix_ext}${side}_range</frame_id>
<ignition_frame_id>${tf_prefix_ext}${side}_range</ignition_frame_id>
<frame_id>${tf_prefix}${side}_range</frame_id>
<ignition_frame_id>${tf_prefix}${side}_range</ignition_frame_id>

<update_rate>5.0</update_rate>
<ray>
Expand Down
26 changes: 15 additions & 11 deletions rosbot_description/urdf/rosbot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,43 +1,47 @@
<?xml version='1.0'?>
<robot name="rosbot" xmlns:xacro="http://www.ros.org/wiki/xacro">

<!-- Default arguments -->
<xacro:arg name="use_sim" default="false" />
<xacro:arg name="use_gpu" default="false" />
<xacro:arg name="mecanum" default="false" />
<xacro:arg name="simulation_engine" default="" />
<xacro:arg name="tf_prefix" default="None" />
<xacro:property name="tf_prefix" value="$(arg tf_prefix)" />
<xacro:arg name="namespace" default="" />
<xacro:property name="namespace" value="$(arg namespace)" />

<xacro:if value="${tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="" />
<xacro:if value="${namespace == ''}">
<xacro:property name="tf_prefix" value="" />
</xacro:if>
<xacro:unless value="${ tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="${tf_prefix}_" />
<xacro:unless value="${namespace == ''}">
<xacro:property name="tf_prefix" value="${namespace}_" />
</xacro:unless>

<!-- Include rosbot_macro.urdf.xacro -->
<xacro:include filename="$(find rosbot_description)/urdf/rosbot_macro.urdf.xacro" ns="husarion" />
<xacro:husarion.rosbot_robot
mecanum="$(arg mecanum)"
use_sim="$(arg use_sim)"
use_gpu="$(arg use_gpu)"
simulation_engine="$(arg simulation_engine)"
tf_prefix="$(arg tf_prefix)" />
tf_prefix="${tf_prefix}" />

<!-- Include slamtec_rplidar_a2.urdf.xacro -->
<xacro:include filename="$(find ros_components_description)/urdf/slamtec_rplidar_a2.urdf.xacro" ns="lidar" />
<xacro:lidar.slamtec_rplidar_a2
parent_link="${tf_prefix_ext}cover_link"
parent_link="${tf_prefix}cover_link"
xyz="0.02 0.0 0.0"
rpy="0.0 0.0 0.0"
use_gpu="$(arg use_gpu)"
simulation_engine="$(arg simulation_engine)"
tf_prefix="$(arg tf_prefix)" />
tf_prefix="${tf_prefix}" />

<!-- Include orbbec_astra.urdf.xacro -->
<xacro:include filename="$(find ros_components_description)/urdf/orbbec_astra.urdf.xacro" ns="camera" />
<xacro:camera.orbbec_astra
parent_link="${tf_prefix_ext}camera_link"
parent_link="${tf_prefix}camera_link"
xyz="0.0 0.0 0.0"
rpy="0.0 0.0 0.0"
simulation_engine="$(arg simulation_engine)"
tf_prefix="$(arg tf_prefix)" />
tf_prefix="${tf_prefix}" />

</robot>
45 changes: 19 additions & 26 deletions rosbot_description/urdf/rosbot_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,6 @@
<xacro:property name="wheel_radius" value="0.0425" />
</xacro:unless>

<xacro:if value="${tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="" />
</xacro:if>
<xacro:unless value="${tf_prefix == 'None'}">
<xacro:property name="tf_prefix_ext" value="${tf_prefix}_" />
</xacro:unless>


<!-- INCLUDE ROBOT PARTS DEFINITIONS -->
<xacro:include filename="$(find rosbot_description)/urdf/body.urdf.xacro" ns="body" />
Expand Down Expand Up @@ -69,7 +62,7 @@
fr_wheel_joint,
fl_wheel_joint
</param>
<param name="tf_prefix">${tf_prefix_ext}</param>
<param name="tf_prefix">${tf_prefix}</param>
</xacro:unless>

<xacro:if value="$(arg use_sim)">
Expand All @@ -82,22 +75,22 @@
</xacro:if>
</hardware>

<joint name="${tf_prefix_ext}fl_wheel_joint">
<joint name="${tf_prefix}fl_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="${tf_prefix_ext}fr_wheel_joint">
<joint name="${tf_prefix}fr_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="${tf_prefix_ext}rl_wheel_joint">
<joint name="${tf_prefix}rl_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="${tf_prefix_ext}rr_wheel_joint">
<joint name="${tf_prefix}rr_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
Expand Down Expand Up @@ -138,16 +131,16 @@
</ros>
</plugin>
</gazebo>
<gazebo reference="${tf_prefix_ext}imu_link">
<gazebo reference="${tf_prefix}imu_link">
<sensor name="imu" type="imu">
<plugin filename="ignition-gazebo-imu-system" name="ignition::gazebo::systems::Imu"></plugin>
<always_on>true</always_on>
<update_rate>25</update_rate>
<topic>imu/data_raw</topic>
<visualize>false</visualize>
<enable_metrics>false</enable_metrics>
<frame_id>${tf_prefix_ext}imu_link</frame_id>
<ignition_frame_id>${tf_prefix_ext}imu_link</ignition_frame_id>
<frame_id>${tf_prefix}imu_link</frame_id>
<ignition_frame_id>${tf_prefix}imu_link</ignition_frame_id>
</sensor>
</gazebo>
</xacro:if>
Expand All @@ -160,10 +153,10 @@
<ros></ros>
<update_rate>10.0</update_rate>
<num_wheel_pairs>2</num_wheel_pairs>
<left_joint>${tf_prefix_ext}fl_wheel_joint</left_joint>
<right_joint>${tf_prefix_ext}fr_wheel_joint</right_joint>
<left_joint>${tf_prefix_ext}rl_wheel_joint</left_joint>
<right_joint>${tf_prefix_ext}rr_wheel_joint</right_joint>
<left_joint>${tf_prefix}fl_wheel_joint</left_joint>
<right_joint>${tf_prefix}fr_wheel_joint</right_joint>
<left_joint>${tf_prefix}rl_wheel_joint</left_joint>
<right_joint>${tf_prefix}rr_wheel_joint</right_joint>
<wheel_separation>0.192</wheel_separation>
<wheel_separation>0.192</wheel_separation>
<wheel_diameter>${wheel_radius*2.0}</wheel_diameter>
Expand All @@ -173,22 +166,22 @@
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
<odometry_frame>${tf_prefix_ext}odom</odometry_frame>
<robot_base_frame>${tf_prefix_ext}base_link</robot_base_frame>
<odometry_frame>${tf_prefix}odom</odometry_frame>
<robot_base_frame>${tf_prefix}base_link</robot_base_frame>
</plugin>
</gazebo>
</xacro:unless>
<!-- publish joint states -->
<gazebo>
<plugin name="joint_states" filename="libgazebo_ros_joint_state_publisher.so">
<joint_name>${tf_prefix_ext}fl_wheel_joint</joint_name>
<joint_name>${tf_prefix_ext}fr_wheel_joint</joint_name>
<joint_name>${tf_prefix_ext}rl_wheel_joint</joint_name>
<joint_name>${tf_prefix_ext}rr_wheel_joint</joint_name>
<joint_name>${tf_prefix}fl_wheel_joint</joint_name>
<joint_name>${tf_prefix}fr_wheel_joint</joint_name>
<joint_name>${tf_prefix}rl_wheel_joint</joint_name>
<joint_name>${tf_prefix}rr_wheel_joint</joint_name>
</plugin>
</gazebo>
<!-- publish IMU -->
<gazebo reference="${tf_prefix_ext}imu_link">
<gazebo reference="${tf_prefix}imu_link">
<sensor type="imu" name="imu">
<always_on>true</always_on>
<update_rate>25</update_rate>
Expand Down
Loading

0 comments on commit 8cf5bda

Please sign in to comment.