Skip to content

Commit

Permalink
Update URDF, fix mecanum sim, fix laser_filter ns, remove tf renaming
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Dec 9, 2024
1 parent 0ea96ec commit 252192f
Show file tree
Hide file tree
Showing 12 changed files with 79 additions and 79 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ ros2 launch rosbot_gazebo simulation.launch.py
||| `gz_world` | Absolute path to SDF world file. <br/> ***string:*** [`husarion_world.sdf`](https://github.com/husarion/husarion_gz_worlds/blob/main/worlds/husarion_world.sdf) |
||| `robots` | Spawning multiple robots at positions with yaw orientations e.g.robots:='robot1={x: 0.0, y: -1.0}; robot2={x: 1.0, y: -1.0};' <br/> ***string:*** `''` |
||| `x` | Initial robot position in the global 'x' axis. <br/> ***float:*** `0.0` |
||| `y` | Initial robot position in the global 'y' axis. <br/> ***float:***`-2.0` |
||| `y` | Initial robot position in the global 'y' axis. <br/> ***float:*** `2.0` |
||| `z` | Initial robot position in the global 'z' axis. <br/> ***float:*** `0.0` |
||| `roll` | Initial robot 'roll' orientation. <br/> ***float:*** `0.0` |
||| `pitch` | Initial robot 'pitch' orientation. <br/> ***float:*** `0.0` |
Expand Down
2 changes: 1 addition & 1 deletion rosbot_bringup/config/laser_filter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
name: box_filter
type: laser_filters/LaserScanBoxFilter
params:
box_frame: base_link
box_frame: <namespace>/base_link

max_x: 0.1
min_x: -0.12
Expand Down
21 changes: 10 additions & 11 deletions rosbot_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
)
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

from nav2_common.launch import ReplaceString

def generate_launch_description():
microros = LaunchConfiguration("microros")
Expand Down Expand Up @@ -74,25 +74,24 @@ def generate_launch_description():
package="robot_localization",
executable="ekf_node",
output="screen",
parameters=[ekf_config],
remappings=[
("/diagnostics", "diagnostics"),
("/tf", "tf"),
("/tf_static", "tf_static"),
],
parameters=[ekf_config, {"tf_prefix": namespace}],
remappings=[("/diagnostics", "diagnostics")],
namespace=namespace,
)

laser_filter_config = PathJoinSubstitution([rosbot_bringup, "config", "laser_filter.yaml"])

namespace_ext = PythonExpression(["'", namespace, "' + '/' if '", namespace, "' else ''"])

laser_filter_config = ReplaceString(
source_file=laser_filter_config,
replacements={'<namespace>/': namespace_ext}
)

laser_filter_node = Node(
package="laser_filters",
executable="scan_to_scan_filter_chain",
parameters=[laser_filter_config],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
namespace=namespace,
)

Expand Down
6 changes: 2 additions & 4 deletions rosbot_controller/config/diff_drive_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,7 @@

/**/imu_broadcaster:
ros__parameters:
tf_frame_prefix_enable: false
use_namespace_as_sensor_name_prefix: true

tf_frame_prefix_enable: true
sensor_name: imu
frame_id: imu_link
static_covariance_orientation: [1.9e-3, 0.0, 0.0, 0.0, 1.9e-3, 0.0, 0.0, 0.0, 1.9e-3] # Values taken from datasheet
Expand All @@ -23,7 +21,7 @@

/**/rosbot_base_controller:
ros__parameters:
tf_frame_prefix_enable: false
tf_frame_prefix_enable: true

left_wheel_names: [fl_wheel_joint, rl_wheel_joint]
right_wheel_names: [fr_wheel_joint, rr_wheel_joint]
Expand Down
5 changes: 2 additions & 3 deletions rosbot_controller/config/mecanum_drive_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@

/**/imu_broadcaster:
ros__parameters:
tf_frame_prefix_enable: false
use_namespace_as_sensor_name_prefix: true
tf_frame_prefix_enable: true

sensor_name: imu
frame_id: imu_link
Expand All @@ -23,7 +22,7 @@

/**/rosbot_base_controller:
ros__parameters:
tf_frame_prefix_enable: false
tf_frame_prefix_enable: true

front_left_wheel_name: fl_wheel_joint
front_right_wheel_name: fr_wheel_joint
Expand Down
47 changes: 18 additions & 29 deletions rosbot_controller/launch/controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,23 +51,6 @@ def generate_launch_description():
description="Whether to use mecanum drive controller (otherwise diff drive controller is used)",
)

controller_config_name = PythonExpression(
[
"'mecanum_drive_controller.yaml' if ",
mecanum,
" else 'diff_drive_controller.yaml'",
]
)

namespace_ext = PythonExpression(
["''", " if '", namespace, "' == '' ", "else ", "'", namespace, "/'"]
)

controller_manager_name = LaunchConfiguration(
"controller_manager_name",
default=[namespace_ext, "controller_manager"],
)

robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
Expand All @@ -89,7 +72,11 @@ def generate_launch_description():
)
robot_description = {"robot_description": robot_description_content}

robot_controllers = PathJoinSubstitution(
controller_config_name = PythonExpression(
["'mecanum_drive_controller.yaml' if ", mecanum, " else 'diff_drive_controller.yaml'"]
)

controllers_config_file = PathJoinSubstitution(
[
FindPackageShare("rosbot_controller"),
"config",
Expand All @@ -100,24 +87,26 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_description, controllers_config_file],
remappings=[
("imu_sensor_node/imu", "/_imu/data_raw"),
("~/motors_cmd", "/_motors_cmd"),
("~/motors_response", "/_motors_response"),
("rosbot_base_controller/cmd_vel", "cmd_vel"),
("/tf", "tf"),
("/tf_static", "tf_static"),
],
condition=UnlessCondition(use_sim),
namespace=namespace,
)

namespace_ext = PythonExpression(["'", namespace, "' + '/' if '", namespace, "' else ''"])

robot_state_pub_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
parameters=[robot_description],
remappings=[("/tf", "tf"), ("/tf_static", "tf_static")],
parameters=[
{"robot_description": robot_description_content},
{"frame_prefix": namespace_ext},
],
namespace=namespace,
)

Expand All @@ -127,11 +116,11 @@ def generate_launch_description():
arguments=[
"joint_state_broadcaster",
"--controller-manager",
controller_manager_name,
"controller_manager",
"--controller-manager-timeout",
"10",
],
remappings=[("/tf", "tf"), ("/tf_static", "tf_static")],
namespace=namespace,
)

robot_controller_spawner = Node(
Expand All @@ -140,11 +129,11 @@ def generate_launch_description():
arguments=[
"rosbot_base_controller",
"--controller-manager",
controller_manager_name,
"controller_manager",
"--controller-manager-timeout",
"10",
],
remappings=[("/tf", "tf"), ("/tf_static", "tf_static")],
namespace=namespace,
)

imu_broadcaster_spawner = Node(
Expand All @@ -153,11 +142,11 @@ def generate_launch_description():
arguments=[
"imu_broadcaster",
"--controller-manager",
controller_manager_name,
"controller_manager",
"--controller-manager-timeout",
"10",
],
remappings=[("/tf", "tf"), ("/tf_static", "tf_static")],
namespace=namespace,
)

# spawners expect ros2_control_node to be running
Expand Down
6 changes: 3 additions & 3 deletions rosbot_description/urdf/body.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
<mesh filename="package://rosbot_description/meshes/body.stl" scale="0.001 0.001 0.001" />
</geometry>
<origin xyz="0.0 0.0 -0.0173" rpy="${pi/2} 0.0 ${pi/2}" />
<material name="White">
<color rgba="1.0 1.0 1.0 1.0" />
<material name="Black">
<color rgba="0.1 0.1 0.1 0.1" />
</material>
</visual>

Expand All @@ -39,7 +39,7 @@
</inertial>
</link>
<gazebo reference="body_link">
<material>Gazebo/White</material>
<material>Gazebo/Black</material>
</gazebo>

<joint name="body_to_cover_joint" type="fixed">
Expand Down
16 changes: 9 additions & 7 deletions rosbot_description/urdf/rosbot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<xacro:arg name="namespace" default="None" />

<xacro:include filename="$(find rosbot_description)/urdf/rosbot_macro.urdf.xacro" ns="husarion" />
<xacro:husarion.rosbot_robot
<xacro:husarion.rosbot
mecanum="$(arg mecanum)"
use_sim="$(arg use_sim)"
namespace="$(arg namespace)" />
Expand All @@ -16,12 +16,14 @@
parent_link="cover_link"
xyz="0.02 0.0 0.0"
rpy="0.0 0.0 0.0"
model="a3" />
model="s2"
namespace="$(arg namespace)" />

<xacro:include filename="$(find ros_components_description)/urdf/orbbec_astra.urdf.xacro" ns="camera" />
<xacro:camera.orbbec_astra
parent_link="camera_mount_link"
xyz="0.0 0.0 0.0"
rpy="0.0 0.0 0.0" />
<xacro:include filename="$(find depthai_descriptions)/urdf/include/depthai_macro.urdf.xacro" ns="camera" />
<xacro:camera.depthai_camera camera_name="oak_camera" parent="camera_mount_link"
camera_model="OAK-D-PRO" base_frame="oak_camera"
cam_pos_x="0.0" cam_pos_y="0.0" cam_pos_z="0.02"
cam_roll="0.0" cam_pitch="0.0" cam_yaw="0.0"
r="0.2" g="0.2" b="0.2" a="1.0" rs_compat="false" simulation="$(arg use_sim)" />

</robot>
3 changes: 1 addition & 2 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 namespace">
<xacro:macro name="rosbot" params="mecanum use_sim namespace">

<xacro:property name="ns" value="${namespace + '/' if namespace != 'None' else ''}" />
<xacro:property name="wheel_radius" value="${0.0470 if mecanum else 0.0425}" />
Expand Down Expand Up @@ -116,7 +116,6 @@
<namespace>${namespace}</namespace>
</xacro:unless>
<remapping>rosbot_base_controller/cmd_vel:=cmd_vel</remapping>
<remapping>/tf:=tf</remapping>
</ros>
</plugin>
</gazebo>
Expand Down
40 changes: 29 additions & 11 deletions rosbot_description/urdf/wheel.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -44,15 +44,15 @@
<xacro:property name="fdir" value="1.0 1.0 0.0" />
</xacro:if>
<xacro:if value="${side == 'rl'}">
<xacro:property name="x" value="${-wheel_separation_x/2}" />
<xacro:property name="y" value="${wheel_separation_y/2}" />
<xacro:property name="x" value="${-wheel_separation_x/2.0}" />
<xacro:property name="y" value="${wheel_separation_y/2.0}" />
<xacro:property name="mesh" value="package://rosbot_description/meshes/${wheel_file}_a.dae" />
<xacro:property name="visual_rotation" value="${0.0}" />
<xacro:property name="fdir" value="1.0 1.0 0.0" />
</xacro:if>
<xacro:if value="${side == 'rr'}">
<xacro:property name="x" value="${-wheel_separation_x/2}" />
<xacro:property name="y" value="${-wheel_separation_y/2}" />
<xacro:property name="x" value="${-wheel_separation_x/2.0}" />
<xacro:property name="y" value="${-wheel_separation_y/2.0}" />
<xacro:property name="mesh" value="package://rosbot_description/meshes/${wheel_file}_b.dae" />
<xacro:property name="visual_rotation" value="${0.0}" />
<xacro:property name="fdir" value="1.0 -1.0 0.0" />
Expand Down Expand Up @@ -90,21 +90,39 @@
</inertial>
</link>

<xacro:if value="${mecanum}">
<gazebo reference="${side}_wheel_link" xmlns:ignition="http://ignitionrobotics.org/schema">
<gazebo reference="${side}_wheel_link" xmlns:gz="http://gazeborobotics.org/schema">
<xacro:unless value="${mecanum}">
<collision>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.0</mu2>
<fdir1 ignition:expressed_in="base_link">${fdir}</fdir1>
<mu>1</mu>
<mu2>1</mu2>
<slip1>0.035</slip1>
<slip2>0</slip2>
<fdir1>0 0 1</fdir1>
</ode>
</friction>
</surface>
</collision>
</gazebo>
</xacro:if>
</xacro:unless>

<xacro:if value="${mecanum}">
<collision>
<surface>
<friction>
<ode>
<mu>0.8</mu>
<mu2>0.2</mu2>
<slip1>0.035</slip1>
<slip2>0</slip2>
<fdir1 gz:expressed_in="base_link">${fdir}</fdir1>
</ode>
</friction>
</surface>
</collision>
</xacro:if>
</gazebo>

</xacro:macro>
</robot>
4 changes: 2 additions & 2 deletions rosbot_gazebo/launch/simulation.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@

def generate_launch_description():
namespace = LaunchConfiguration("namespace")
x = LaunchConfiguration("x", default="0.0")
y = LaunchConfiguration("y", default="2.0")
x = LaunchConfiguration("x", default="-1.0")
y = LaunchConfiguration("y", default="-2.0")
z = LaunchConfiguration("z", default="0.0")
roll = LaunchConfiguration("roll", default="0.0")
pitch = LaunchConfiguration("pitch", default="0.0")
Expand Down
6 changes: 1 addition & 5 deletions rosbot_gazebo/launch/spawn.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ def generate_launch_description():
)

declare_x_arg = DeclareLaunchArgument(
"x", default_value="0.0", description="Initial robot position in the global 'x' axis."
"x", default_value="-1.0", description="Initial robot position in the global 'x' axis."
)

declare_y_arg = DeclareLaunchArgument(
Expand Down Expand Up @@ -128,10 +128,6 @@ def generate_launch_description():
executable="parameter_bridge",
name="ros_gz_bridge",
parameters=[{"config_file": namespaced_gz_remappings_file}],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
namespace=namespace,
)

Expand Down

0 comments on commit 252192f

Please sign in to comment.