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

Launch cooperative perception nodes #2195

Merged
merged 3 commits into from
Nov 21, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
125 changes: 123 additions & 2 deletions carma/launch/environment.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,8 @@ def generate_launch_description():
carma_wm_ctrl_param_file = os.path.join(
get_package_share_directory('carma_wm_ctrl'), 'config/parameters.yaml')


carma_cooperative_perception_param_file = os.path.join(
get_package_share_directory('carma_cooperative_perception'), 'config/params.yaml')
Copy link
Contributor

Choose a reason for hiding this comment

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

The recommended way to do paths now is with pathlib. This should be refactored to something like this:

carma_cooperative_perception_param_file = str(get_package_share_directory("carma_cooperative_perception") / "config/params.yaml")

Copy link
Contributor Author

Choose a reason for hiding this comment

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

imported pathlib to handle this


# lidar_perception_container contains all nodes for lidar based object perception
# a failure in any one node in the chain would invalidate the rest of it, so they can all be
Expand Down Expand Up @@ -284,7 +285,8 @@ def generate_launch_description():
("incoming_mobility_path", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_mobility_path" ] ),
("incoming_psm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_psm" ] ),
("incoming_bsm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_bsm" ] ),
("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] )
("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
("external_objects", "fused_external_objects")
],
parameters=[
motion_computation_param_file,
Expand Down Expand Up @@ -399,6 +401,124 @@ def generate_launch_description():
)
]
)

# Cooperative Perception Stack
carma_cooperative_perception_container = ComposableNodeContainer(
package='carma_ros2_utils', # rclcpp_components
name='carma_cooperative_perception_container',
executable='carma_component_container_mt',
namespace= GetCurrentNamespace(),
composable_node_descriptions=[
ComposableNode(
package='carma_cooperative_perception',
plugin='carma_cooperative_perception::ExternalObjectListToDetectionListNode',
name='cp_external_object_list_to_detection_list_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('cp_external_object_list_to_detection_list_node', env_log_levels) },
{'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
MishkaMN marked this conversation as resolved.
Show resolved Hide resolved
],
remappings=[
("input/georeference", "georeference"),
("output/detections", "full_detection_list"),
("input/external_objects", "external_objects"),
],
parameters=[
carma_cooperative_perception_param_file
]
),
ComposableNode(
package='carma_cooperative_perception',
plugin='carma_cooperative_perception::ExternalObjectListToSdsmNode',
name='cp_external_object_list_to_sdsm_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('cp_external_object_list_to_sdsm_node', env_log_levels) },
{'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
],
remappings=[
("input/georeference", "georeference"),
("output/sdsms", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/outgoing_sdsm" ] ),
("input/pose_stamped", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
("input/external_objects", "external_objects"),
],
parameters=[
carma_cooperative_perception_param_file
]
),
ComposableNode(
package='carma_cooperative_perception',
plugin='carma_cooperative_perception::HostVehicleFilterNode',
name='cp_host_vehicle_filter_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('cp_host_vehicle_filter_node', env_log_levels) },
{'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
],
remappings=[
("input/host_vehicle_pose", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/current_pose" ] ),
("input/detection_list", "full_detection_list"),
("output/detection_list", "filtered_detection_list")
],
parameters=[
carma_cooperative_perception_param_file
]
),
ComposableNode(
package='carma_cooperative_perception',
plugin='carma_cooperative_perception::SdsmToDetectionListNode',
name='cp_sdsm_to_detection_list_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('cp_sdsm_to_detection_list_node', env_log_levels) },
{'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
],
remappings=[
("input/sdsm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_sdsm" ] ),
("output/detections", "full_detection_list"),
],
parameters=[
carma_cooperative_perception_param_file
]
),
ComposableNode(
package='carma_cooperative_perception',
plugin='carma_cooperative_perception::TrackListToExternalObjectListNode',
name='cp_track_list_to_external_object_list_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('cp_track_list_to_external_object_list_node', env_log_levels) },
{'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
],
remappings=[
("input/track_list", "cooperative_perception_track_list"),
("output/external_object_list", "fused_external_objects"),
],
parameters=[
carma_cooperative_perception_param_file
]
),
ComposableNode(
package='carma_cooperative_perception',
plugin='carma_cooperative_perception::MultipleObjectTrackerNode',
name='cp_multiple_object_tracker_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('cp_multiple_object_tracker_node', env_log_levels) },
{'is_lifecycle_node': True} # Flag to allow lifecycle node loading in lifecycle wrapper
],
remappings=[
("output/track_list", "cooperative_perception_track_list"),
("input/detection_list", "filtered_detection_list"),
],
parameters=[
carma_cooperative_perception_param_file
]
),

]
)

# subsystem_controller which orchestrates the lifecycle of this subsystem's components
subsystem_controller = Node(
package='subsystem_controllers',
Expand All @@ -418,5 +538,6 @@ def generate_launch_description():
carma_external_objects_container,
lanelet2_map_loader_container,
lanelet2_map_visualization_container,
carma_cooperative_perception_container,
subsystem_controller
])
5 changes: 3 additions & 2 deletions carma_cooperative_perception/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,9 @@ rclcpp_components_register_nodes(carma_cooperative_perception
"carma_cooperative_perception::ExternalObjectListToDetectionListNode"
"carma_cooperative_perception::ExternalObjectListToSdsmNode"
"carma_cooperative_perception::SdsmToDetectionListNode"
"carma_cooperative_perception::TrackListToExternalObjectListComponent"
"carma_cooperative_perception::MultipleObjectTrackerComponent"
"carma_cooperative_perception::TrackListToExternalObjectListNode"
"carma_cooperative_perception::MultipleObjectTrackerNode"
"carma_cooperative_perception::HostVehicleFilterNode"
)

ament_auto_add_executable(external_object_list_to_detection_list_node
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <carma_cooperative_perception_interfaces/msg/detection.hpp>
#include <carma_ros2_utils/carma_lifecycle_node.hpp>
#include <rclcpp_components/register_node_macro.hpp>

#include <vector>

Expand Down Expand Up @@ -188,3 +189,11 @@ auto euclidean_distance_squared(
}

} // namespace carma_cooperative_perception


// This is not our macro, so we should not worry about linting it.
// clang-tidy added support for ignoring system macros in release 14.0.0 (see the release notes
// here: https://releases.llvm.org/14.0.0/tools/clang/tools/extra/docs/ReleaseNotes.html), but
// ament_clang_tidy for ROS 2 Foxy specifically looks for clang-tidy-6.0.
RCLCPP_COMPONENTS_REGISTER_NODE( // NOLINT
carma_cooperative_perception::HostVehicleFilterNode) // NOLINT
Original file line number Diff line number Diff line change
Expand Up @@ -85,3 +85,9 @@ auto TrackListToExternalObjectListNode::publish_as_external_object_list(
}

} // namespace carma_cooperative_perception

// This is not our macro, so we should not worry about linting it.
// clang-tidy added support for ignoring system macros in release 14.0.0 (see the release notes
// here: https://releases.llvm.org/14.0.0/tools/clang/tools/extra/docs/ReleaseNotes.html), but
// ament_clang_tidy for ROS 2 Foxy specifically looks for clang-tidy-6.0.
RCLCPP_COMPONENTS_REGISTER_NODE(carma_cooperative_perception::TrackListToExternalObjectListNode) // NOLINT