Skip to content

Commit

Permalink
Updated chassis with logo, Imu always on, camera and Lidar as launch …
Browse files Browse the repository at this point in the history
…param
  • Loading branch information
D-1shu authored and ggupta9777 committed Jun 28, 2023
1 parent 50f8e30 commit cdb37db
Show file tree
Hide file tree
Showing 15 changed files with 209 additions and 867 deletions.
21 changes: 4 additions & 17 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -141,22 +141,9 @@ ros2 launch new_bcr_robot gz.launch.py
world_file:=small_warehouse.world
```

### World File Configurations

The `worlds` directory has two subdirectories: `gazebo` and `gz`. Both of these host world file for each simulator respectively. Here are the expected outputs from each world configuration:

1. Gazebo Classic (small_warehouse):

Launch file Change in the Launch Description:
```python
DeclareLaunchArgument(
'world', default_value=[FindPackageShare('new_bcr_robot'), '/worlds/small_warehouse.world'],
)
```
![](res/gazebo.jpg)

2. Gz Sim (Ignition Gazebo) (small_warehouse World):
![](res/gz.png)
### Simulation and Visualization
1. Gz Sim (Ignition Gazebo) (small_warehouse World):
![](res/gz.jpg)

2. Rviz (Depth camera) (small_warehouse World):
![](res/rviz.png)
![](res/rviz.jpg)
38 changes: 30 additions & 8 deletions launch/gazebo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.substitutions import LaunchConfiguration, Command
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch_ros.actions import Node
Expand All @@ -20,27 +20,44 @@ def get_xacro_to_doc(xacro_file_path, mappings):
def generate_launch_description():
# Retrieve launch configuration arguments
use_sim_time = LaunchConfiguration('use_sim_time', default='true')
position_x = LaunchConfiguration("position_x")
position_y = LaunchConfiguration("position_y")
orientation_yaw = LaunchConfiguration("orientation_yaw")
camera_enabled = LaunchConfiguration("camera_enabled", default=True)
two_d_lidar_enabled = LaunchConfiguration("two_d_lidar_enabled", default=True)

# Path to the Xacro file
xacro_path = join(get_package_share_directory('new_bcr_robot'), 'urdf', 'new_bcr_robot.xacro')
doc = get_xacro_to_doc(xacro_path, {"wheel_odom_topic": "odom", "sim_gazebo": "true", "two_d_lidar_enabled": "true", "camera_enabled": "true"})
#doc = get_xacro_to_doc(xacro_path, {"wheel_odom_topic": "odom", "sim_gazebo": "true", "two_d_lidar_enabled": "true", "camera_enabled": "true"})

# Launch the robot_state_publisher node
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[{'use_sim_time': use_sim_time}, {'robot_description': doc.toxml()}],
remappings=[('joint_states', '/new_bcr_robot/joint_states')]
parameters=[{"use_sim_time": use_sim_time},
{'robot_description': Command( \
['xacro ', join(xacro_path),
' camera_enabled:=', camera_enabled,
' two_d_lidar_enabled:=', two_d_lidar_enabled,
' sim_gazebo:=', "true"
])}]
)

# Launch the spawn_entity node to spawn the robot in Gazebo
spawn_entity = Node(
package='gazebo_ros',
executable='spawn_entity.py',
arguments=['-topic', 'robot_description', '-entity', 'new_bcr_robot'],
output='screen'
output='screen',
arguments=[
'-topic', "/robot_description",
'-entity', "new_bcr_robot",
'-z', "0.28",
'-x', position_x,
'-y', position_y,
'-Y', orientation_yaw
]
)

# Include the Gazebo launch file
Expand All @@ -51,11 +68,16 @@ def generate_launch_description():

return LaunchDescription([
# Declare launch arguments
DeclareLaunchArgument('world', default_value=[FindPackageShare('new_bcr_robot'), '/worlds/gazebo/small_warehouse.world']),
DeclareLaunchArgument('world', default_value=[FindPackageShare('new_bcr_robot'), '/worlds/small_warehouse.sdf']),
DeclareLaunchArgument('gui', default_value='true'),
DeclareLaunchArgument('verbose', default_value='false'),
DeclareLaunchArgument('use_sim_time', default_value='true'),
DeclareLaunchArgument('robot_description', default_value=doc.toxml()),
DeclareLaunchArgument("camera_enabled", default_value = camera_enabled),
DeclareLaunchArgument("two_d_lidar_enabled", default_value = two_d_lidar_enabled),
DeclareLaunchArgument("position_x", default_value="0.0"),
DeclareLaunchArgument("position_y", default_value="0.0"),
DeclareLaunchArgument("orientation_yaw", default_value="0.0"),
# DeclareLaunchArgument('robot_description', default_value=doc.toxml()),
gazebo,
robot_state_publisher,
spawn_entity
Expand Down
51 changes: 29 additions & 22 deletions launch/gz.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.substitutions import LaunchConfiguration, Command
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch_ros.actions import Node
Expand All @@ -21,30 +21,34 @@ def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time", default=True)

new_bcr_robot_path = get_package_share_directory("new_bcr_robot")
world_file = LaunchConfiguration("world_file", default = "-r " + join(new_bcr_robot_path, "worlds", "gz", "small_warehouse.sdf"))
world_file = LaunchConfiguration("world_file", default = "-r " + join(new_bcr_robot_path, "worlds", "small_warehouse.sdf"))

position_x = LaunchConfiguration("x")
position_y = LaunchConfiguration("y")
orientation_yaw = LaunchConfiguration("yaw")
position_x = LaunchConfiguration("position_x")
position_y = LaunchConfiguration("position_y")
orientation_yaw = LaunchConfiguration("orientation_yaw")
camera_enabled = LaunchConfiguration("camera_enabled", default=True)
two_d_lidar_enabled = LaunchConfiguration("two_d_lidar_enabled", default=True)

robot_description_content = get_xacro_to_doc(
join(new_bcr_robot_path, "urdf", "new_bcr_robot.xacro"),
{"wheel_odom_topic": "odom",
"sim_gz": "true",
"two_d_lidar_enabled": "true",
"conveyor_enabled": "false",
"camera_enabled": "true"
}
).toxml()
# robot_description_content = get_xacro_to_doc(
# join(new_bcr_robot_path, "urdf", "new_bcr_robot.xacro"),
# {"sim_gz": "true",
# "two_d_lidar_enabled": "true",
# "conveyor_enabled": "false",
# "camera_enabled": "true"
# }
# ).toxml()

robot_state_publisher = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
name="robot_state_publisher",
parameters=[
{"use_sim_time": use_sim_time},
{"robot_description": robot_description_content}
]
parameters=[{"use_sim_time": use_sim_time},
{'robot_description': Command( \
['xacro ', join(new_bcr_robot_path, 'urdf/new_bcr_robot.xacro'),
' camera_enabled:=', camera_enabled,
' two_d_lidar_enabled:=', two_d_lidar_enabled,
' sim_gz:=', "true"
])}]
)

gz_sim_share = get_package_share_directory("ros_gz_sim")
Expand Down Expand Up @@ -80,7 +84,8 @@ def generate_launch_description():
"/scan@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/depth_camera@sensor_msgs/msg/Image[ignition.msgs.Image",
"/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"/depth_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked"
"/depth_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked",
"/imu@sensor_msgs/msg/Imu[ignition.msgs.IMU",
],
)

Expand All @@ -100,9 +105,11 @@ def generate_launch_description():
return LaunchDescription([
DeclareLaunchArgument("use_sim_time", default_value=use_sim_time),
DeclareLaunchArgument("world_file", default_value=world_file),
DeclareLaunchArgument("x", default_value="0.0"),
DeclareLaunchArgument("y", default_value="0.0"),
DeclareLaunchArgument("yaw", default_value="0.0"),
DeclareLaunchArgument("camera_enabled", default_value = camera_enabled),
DeclareLaunchArgument("two_d_lidar_enabled", default_value = two_d_lidar_enabled),
DeclareLaunchArgument("position_x", default_value="0.0"),
DeclareLaunchArgument("position_y", default_value="0.0"),
DeclareLaunchArgument("orientation_yaw", default_value="0.0"),
robot_state_publisher,
gz_sim, gz_spawn_entity, gz_ros2_bridge,
transform_publisher
Expand Down
Loading

0 comments on commit cdb37db

Please sign in to comment.