Skip to content

Commit

Permalink
Added namespace to robot description
Browse files Browse the repository at this point in the history
Signed-off-by: Jakub Delicat <jakub.delicat@husarion.com>
  • Loading branch information
delihus committed Nov 13, 2023
1 parent 2b479a6 commit ae14e26
Show file tree
Hide file tree
Showing 7 changed files with 126 additions and 78 deletions.
1 change: 1 addition & 0 deletions .wordlist.txt
Original file line number Diff line number Diff line change
Expand Up @@ -120,3 +120,4 @@ Palacios
env
pids
pgrep
namespace
4 changes: 3 additions & 1 deletion rosbot_controller/launch/controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,8 @@ def generate_launch_description():
use_gpu,
" simulation_engine:=",
simulation_engine,
" tf_prefix:=",
namespace,
]
)
robot_description = {"robot_description": robot_description_content}
Expand Down Expand Up @@ -215,7 +217,7 @@ def generate_launch_description():
declare_use_gpu_arg,
declare_simulation_engine_arg,
declare_controller_manager_name_arg,
SetParameter("use_sim_time"),
SetParameter("use_sim_time", value=use_sim),
control_node,
robot_state_pub_node,
joint_state_broadcaster_spawner,
Expand Down
55 changes: 31 additions & 24 deletions rosbot_description/urdf/body.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,18 +1,25 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- body defining macro -->
<xacro:macro name="body" params="wheel_radius mecanum use_gpu">
<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" />

<link name="base_link" />
<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="base_to_body_joint" type="fixed">
<link name="${tf_prefix_ext}base_link" />

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

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

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

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

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

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

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

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

<xacro:range_sensor.vl53lox parent="body_link" xyz="0.0926 0.05 0.015" rpy="0.0 0.0 ${radians(12.5)}" prefix="fl" />
<xacro:range_sensor.vl53lox parent="body_link" xyz="0.0926 -0.05 0.015" rpy="0.0 0.0 ${radians(-12.5)}" prefix="fr" />
<xacro:range_sensor.vl53lox parent="body_link" xyz="-0.0926 0.05 0.0115" rpy="0.0 0.0 ${radians(167.5)}" prefix="rl" />
<xacro:range_sensor.vl53lox parent="body_link" xyz="-0.0926 -0.05 0.0115" rpy="0.0 0.0 ${radians(192.5)}" prefix="rr" />
<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:macro>
</robot>
25 changes: 16 additions & 9 deletions rosbot_description/urdf/components/vl53lox.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,25 +1,32 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- vl53lox defining macro -->
<xacro:macro name="vl53lox" params="parent xyz rpy prefix">
<xacro:macro name="vl53lox" params="parent xyz rpy side tf_prefix">

<joint name="${parent}_${prefix}_range_joint" type="fixed">
<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">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent}" />
<child link="${prefix}_range" />
<child link="${tf_prefix_ext}${side}_range" />
</joint>

<link name="${prefix}_range" />
<link name="${tf_prefix_ext}${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="${prefix}_range">
<sensor name="${prefix}_range" type='gpu_lidar'>
<gazebo reference="${tf_prefix_ext}${side}_range">
<sensor name="${tf_prefix_ext}${side}_range" type='gpu_lidar'>

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

<update_rate>5.0</update_rate>
<ray>
Expand Down
26 changes: 21 additions & 5 deletions rosbot_description/urdf/rosbot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,23 +5,39 @@
<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: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>

<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)"/>
<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)" />

<xacro:include filename="$(find ros_components_description)/urdf/slamtec_rplidar_a2.urdf.xacro" ns="lidar" />
<xacro:lidar.slamtec_rplidar_a2
parent_link="cover_link"
parent_link="${tf_prefix_ext}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)" />
simulation_engine="$(arg simulation_engine)"
tf_prefix="$(arg tf_prefix)" />

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

</robot>
64 changes: 36 additions & 28 deletions rosbot_description/urdf/rosbot_macro.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version='1.0'?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="rosbot_robot" params="mecanum use_sim use_gpu simulation_engine">
<xacro:macro name="rosbot_robot" params="mecanum use_sim use_gpu tf_prefix simulation_engine">

<xacro:if value="${mecanum}">
<xacro:property name="wheel_radius" value="0.0470" />
Expand All @@ -9,18 +9,26 @@
<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" />
<xacro:include filename="$(find rosbot_description)/urdf/wheel.urdf.xacro" ns="wheel" />

<!-- BODY DECLARATION -->
<xacro:body.body wheel_radius="${wheel_radius}" mecanum="${mecanum}" use_gpu="${use_gpu}" />
<xacro:body.body wheel_radius="${wheel_radius}" mecanum="${mecanum}" use_gpu="${use_gpu}" tf_prefix="${tf_prefix}" />

<!-- WHEEL DECLARATION -->
<xacro:wheel.wheel wheel_radius="${wheel_radius}" prefix="fr" mecanum="${mecanum}" />
<xacro:wheel.wheel wheel_radius="${wheel_radius}" prefix="fl" mecanum="${mecanum}" />
<xacro:wheel.wheel wheel_radius="${wheel_radius}" prefix="rl" mecanum="${mecanum}" />
<xacro:wheel.wheel wheel_radius="${wheel_radius}" prefix="rr" mecanum="${mecanum}" />
<xacro:wheel.wheel wheel_radius="${wheel_radius}" side="fr" mecanum="${mecanum}" tf_prefix="${tf_prefix}" />
<xacro:wheel.wheel wheel_radius="${wheel_radius}" side="fl" mecanum="${mecanum}" tf_prefix="${tf_prefix}" />
<xacro:wheel.wheel wheel_radius="${wheel_radius}" side="rl" mecanum="${mecanum}" tf_prefix="${tf_prefix}" />
<xacro:wheel.wheel wheel_radius="${wheel_radius}" side="rr" mecanum="${mecanum}" tf_prefix="${tf_prefix}" />

<!-- ROS2 CONTROL -->
<xacro:unless value="$(arg use_sim)">
Expand Down Expand Up @@ -54,10 +62,10 @@

<!-- order of velocity commands to be published in motors_cmd Float32MultiArray msg -->
<param name="velocity_command_joint_order">
rr_wheel_joint,
rl_wheel_joint,
fr_wheel_joint,
fl_wheel_joint
${tf_prefix_ext}rr_wheel_joint,
${tf_prefix_ext}rl_wheel_joint,
${tf_prefix_ext}fr_wheel_joint,
${tf_prefix_ext}fl_wheel_joint
</param>
</xacro:unless>

Expand All @@ -71,22 +79,22 @@
</xacro:if>
</hardware>

<joint name="fl_wheel_joint">
<joint name="${tf_prefix_ext}fl_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="fr_wheel_joint">
<joint name="${tf_prefix_ext}fr_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="rl_wheel_joint">
<joint name="${tf_prefix_ext}rl_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="rr_wheel_joint">
<joint name="${tf_prefix_ext}rr_wheel_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
Expand Down Expand Up @@ -127,16 +135,16 @@
</ros>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<gazebo reference="${tf_prefix_ext}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>imu_link</frame_id>
<ignition_frame_id>imu_link</ignition_frame_id>
<frame_id>${tf_prefix_ext}imu_link</frame_id>
<ignition_frame_id>${tf_prefix_ext}imu_link</ignition_frame_id>
</sensor>
</gazebo>
</xacro:if>
Expand All @@ -149,10 +157,10 @@
<ros></ros>
<update_rate>10.0</update_rate>
<num_wheel_pairs>2</num_wheel_pairs>
<left_joint>fl_wheel_joint</left_joint>
<right_joint>fr_wheel_joint</right_joint>
<left_joint>rl_wheel_joint</left_joint>
<right_joint>rr_wheel_joint</right_joint>
<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>
<wheel_separation>0.192</wheel_separation>
<wheel_separation>0.192</wheel_separation>
<wheel_diameter>${wheel_radius*2.0}</wheel_diameter>
Expand All @@ -162,22 +170,22 @@
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
<odometry_frame>${tf_prefix_ext}odom</odometry_frame>
<robot_base_frame>${tf_prefix_ext}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>fl_wheel_joint</joint_name>
<joint_name>fr_wheel_joint</joint_name>
<joint_name>rl_wheel_joint</joint_name>
<joint_name>rr_wheel_joint</joint_name>
<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>
</plugin>
</gazebo>
<!-- publish IMU -->
<gazebo reference="imu_link">
<gazebo reference="${tf_prefix_ext}imu_link">
<sensor type="imu" name="imu">
<always_on>true</always_on>
<update_rate>25</update_rate>
Expand Down
Loading

0 comments on commit ae14e26

Please sign in to comment.