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

[GSOC-95] Custom ros_gz bridge for DVL plugin #14

Merged
merged 14 commits into from
Aug 19, 2024
Merged
Show file tree
Hide file tree
Changes from 10 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions dave_interfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/UsblCommand.msg"
"msg/UsblResponse.msg"
"msg/Location.msg"
"msg/DVL.msg"
"msg/DVLBeam.msg"
"msg/DVLTarget.msg"
"srv/SetOriginSphericalCoord.srv"
"srv/GetOriginSphericalCoord.srv"
"srv/TransformToSphericalCoord.srv"
Expand Down
5 changes: 5 additions & 0 deletions dave_interfaces/msg/DVL.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
std_msgs/Header header
string type
DVLTarget target
geometry_msgs/TwistWithCovariance velocity
DVLBeam[] beams
5 changes: 5 additions & 0 deletions dave_interfaces/msg/DVLBeam.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
int64 id
string reference
float64 range
bool locked
geometry_msgs/TwistWithCovariance velocity
2 changes: 2 additions & 0 deletions dave_interfaces/msg/DVLTarget.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string type
float64 range
4 changes: 2 additions & 2 deletions examples/dave_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ To launch a Dave model directly from a Fuel URI, follow these steps:
2. Launch the model using the specified launch file:

```bash
ros2 launch dave_demos object_in_empty_world.launch.py object_name:='mossy_cinder_block'
ros2 launch dave_demos dave_object.launch.py namespace:='mossy_cinder_block' paused:=false
```

This method simplifies the process by pulling the model directly from Fuel, ensuring you always have the latest version without needing to manage local files.
Expand Down Expand Up @@ -47,7 +47,7 @@ If you prefer to use model files downloaded from Fuel, proceed as follows:
4. Launch the model using the provided launch file:

```bash
ros2 launch dave_demos sensor_in_empty_world.launch.py sensor_name:='nortek_dvl500_300'
ros2 launch dave_demos dave_sensor.launch.py namespace:='nortek_dvl500_300' world_name:=dvl_world paused:=false
```

This approach gives you more control over the models you use, allowing for offline use and customization. It's especially useful when working in environments with limited internet connectivity or when specific model versions are required.
Expand Down
165 changes: 165 additions & 0 deletions examples/dave_demos/launch/dave_object.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, TextSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.conditions import IfCondition
from launch_ros.substitutions import FindPackageShare


def launch_setup(context, *args, **kwargs):
paused = LaunchConfiguration("paused").perform(context)
gui = LaunchConfiguration("gui").perform(context)
use_sim_time = LaunchConfiguration("use_sim_time").perform(context)
headless = LaunchConfiguration("headless").perform(context)
verbose = LaunchConfiguration("verbose").perform(context)
namespace = LaunchConfiguration("namespace").perform(context)
world_name = LaunchConfiguration("world_name").perform(context)
x = LaunchConfiguration("x").perform(context)
y = LaunchConfiguration("y").perform(context)
z = LaunchConfiguration("z").perform(context)
roll = LaunchConfiguration("roll").perform(context)
pitch = LaunchConfiguration("pitch").perform(context)
yaw = LaunchConfiguration("yaw").perform(context)
use_ned_frame = LaunchConfiguration("use_ned_frame").perform(context)

if world_name != "empty.sdf":
world_filename = f"{world_name}.world"
world_filepath = PathJoinSubstitution(
[FindPackageShare("dave_worlds"), "worlds", world_filename]
).perform(context)
gz_args = [world_filepath]
else:
gz_args = [world_name]

if headless == "true":
gz_args.append("-s")
if paused == "false":
gz_args.append("-r")
if verbose == "true":
gz_args.append("--verbose")

gz_args_str = " ".join(gz_args)

gz_sim_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("ros_gz_sim"),
"launch",
"gz_sim.launch.py",
]
)
]
),
launch_arguments=[
("gz_args", TextSubstitution(text=gz_args_str)),
],
condition=IfCondition(gui),
)

object_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("dave_object_models"),
"launch",
"upload_object.launch.py",
]
)
]
),
launch_arguments={
"gui": gui,
"use_sim_time": use_sim_time,
"namespace": namespace,
"x": x,
"y": y,
"z": z,
"roll": roll,

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've just found out that the launch argument roll, pitch ,yaw does not work. It has to be R, P, Y. We should modify from line 80-82, 20-22, and any other launch.py that uses this.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@woensug-choi I just tried launching with all the arguements and seems to work fine. I used the following command:

ros2 launch dave_demos dave_sensor.launch.py namespace:=nortek_dvl500_300 world_name:=dvl_world paused:=false x:=0 y:=1.2 z:=-20 roll:=1.57 pitch:=0.0 yaw:=0.0 headless:=false gui:=true verbose:=true paused:=false

roll, pitch, and yaw are in radians.

I'm not sure why it does not work for you.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If it worked for you. never mind for this PR (as it is not critically related to this)

Copy link
Collaborator Author

@rakeshv24 rakeshv24 Aug 19, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually, you are right. It should be R, R, Y.

I'll make the changes! Thanks for pointing that out!

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Strange! ros2 launch dave_demos dave_sensor.launch.py namespace:=nortek_dvl500_300 world_name:=dvl_world paused:=false x:=0 y:=1.2 z:=-20 roll:=1.57 pitch:=0.0 yaw:=0.0 headless:=false gui:=true verbose:=true paused:=false works find on ubuntu native install machine but causes context error in Mac. (again, if it's only mac problem. ignore for sake of this PR).

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Strange! It works fine for me both on ubuntu native and mac.

@woensug-choi do you think the problem could be coming from here?

I have committed some changes. Please check if the error still occurs.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@rakeshv24 Yes it seems... but don't know why...!

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@woensug-choi it seems that the problem can be resolved by properly shutting down the node. But since this actually does not hinder with the functionality of the code, we can maybe resolve it later. What do you think?

"pitch": pitch,
"yaw": yaw,
"use_ned_frame": use_ned_frame,
}.items(),
)

return [gz_sim_launch, object_launch]


def generate_launch_description():

args = [
DeclareLaunchArgument(
"paused",
default_value="true",
description="Start the simulation paused",
),
DeclareLaunchArgument(
"gui",
default_value="true",
description="Flag to enable the gazebo gui",
),
DeclareLaunchArgument(
"use_sim_time",
default_value="true",
description="Flag to indicate whether to use simulation time",
),
DeclareLaunchArgument(
"headless",
default_value="false",
description="Flag to enable the gazebo headless mode",
),
DeclareLaunchArgument(
"verbose",
default_value="false",
description="Enable verbose mode for Gazebo simulation",
),
DeclareLaunchArgument(
"world_name",
default_value="empty.sdf",
description="Gazebo world file to launch",
),
DeclareLaunchArgument(
"namespace",
default_value="",
description="Namespace",
),
DeclareLaunchArgument(
"x",
default_value="0.0",
description="Initial x position",
),
DeclareLaunchArgument(
"y",
default_value="0.0",
description="Initial y position",
),
DeclareLaunchArgument(
"z",
default_value="0.0",
description="Initial z position",
),
DeclareLaunchArgument(
"roll",
default_value="0.0",
description="Initial roll angle",
),
DeclareLaunchArgument(
"pitch",
default_value="0.0",
description="Initial pitch angle",
),
DeclareLaunchArgument(
"yaw",
default_value="0.0",
description="Initial yaw angle",
),
DeclareLaunchArgument(
"use_ned_frame",
default_value="false",
description="Flag to indicate whether to use the north-east-down frame",
),
]

return LaunchDescription(args + [OpaqueFunction(function=launch_setup)])
165 changes: 165 additions & 0 deletions examples/dave_demos/launch/dave_sensor.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, TextSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.conditions import IfCondition
from launch_ros.substitutions import FindPackageShare


def launch_setup(context, *args, **kwargs):
paused = LaunchConfiguration("paused").perform(context)
gui = LaunchConfiguration("gui").perform(context)
use_sim_time = LaunchConfiguration("use_sim_time").perform(context)
headless = LaunchConfiguration("headless").perform(context)
verbose = LaunchConfiguration("verbose").perform(context)
namespace = LaunchConfiguration("namespace").perform(context)
world_name = LaunchConfiguration("world_name").perform(context)
x = LaunchConfiguration("x").perform(context)
y = LaunchConfiguration("y").perform(context)
z = LaunchConfiguration("z").perform(context)
roll = LaunchConfiguration("roll").perform(context)
pitch = LaunchConfiguration("pitch").perform(context)
yaw = LaunchConfiguration("yaw").perform(context)
use_ned_frame = LaunchConfiguration("use_ned_frame").perform(context)

if world_name != "empty.sdf":
world_filename = f"{world_name}.world"
world_filepath = PathJoinSubstitution(
[FindPackageShare("dave_worlds"), "worlds", world_filename]
).perform(context)
gz_args = [world_filepath]
else:
gz_args = [world_name]

if headless == "true":
gz_args.append("-s")
if paused == "false":
gz_args.append("-r")
if verbose == "true":
gz_args.append("--verbose")

gz_args_str = " ".join(gz_args)

gz_sim_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("ros_gz_sim"),
"launch",
"gz_sim.launch.py",
]
)
]
),
launch_arguments=[
("gz_args", TextSubstitution(text=gz_args_str)),
],
condition=IfCondition(gui),
)

sensor_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("dave_sensor_models"),
"launch",
"upload_sensor.launch.py",
]
)
]
),
launch_arguments={
"gui": gui,
"use_sim_time": use_sim_time,
"namespace": namespace,
"x": x,
"y": y,
"z": z,
"roll": roll,
woensug-choi marked this conversation as resolved.
Show resolved Hide resolved
"pitch": pitch,
"yaw": yaw,
"use_ned_frame": use_ned_frame,
}.items(),
)

return [gz_sim_launch, sensor_launch]


def generate_launch_description():

args = [
DeclareLaunchArgument(
"paused",
default_value="true",
description="Start the simulation paused",
),
DeclareLaunchArgument(
"gui",
default_value="true",
description="Flag to enable the gazebo gui",
),
DeclareLaunchArgument(
"use_sim_time",
default_value="true",
description="Flag to indicate whether to use simulation time",
),
DeclareLaunchArgument(
"headless",
default_value="false",
description="Flag to enable the gazebo headless mode",
),
DeclareLaunchArgument(
"verbose",
default_value="false",
description="Enable verbose mode for Gazebo simulation",
),
DeclareLaunchArgument(
"world_name",
default_value="empty.sdf",
description="Gazebo world file to launch",
),
DeclareLaunchArgument(
"namespace",
default_value="",
description="Namespace",
),
DeclareLaunchArgument(
"x",
default_value="0.0",
description="Initial x position",
),
DeclareLaunchArgument(
"y",
default_value="0.0",
description="Initial y position",
),
DeclareLaunchArgument(
"z",
default_value="0.0",
description="Initial z position",
),
DeclareLaunchArgument(
"roll",
default_value="0.0",
description="Initial roll angle",
),
DeclareLaunchArgument(
"pitch",
default_value="0.0",
description="Initial pitch angle",
),
DeclareLaunchArgument(
"yaw",
default_value="0.0",
description="Initial yaw angle",
),
DeclareLaunchArgument(
"use_ned_frame",
default_value="false",
description="Flag to indicate whether to use the north-east-down frame",
),
]

return LaunchDescription(args + [OpaqueFunction(function=launch_setup)])
Loading
Loading