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

fix failure transferring sensor data from carla to carma #19

Open
wants to merge 5 commits into
base: develop
Choose a base branch
from

Conversation

chengyuan0124
Copy link
Contributor

@chengyuan0124 chengyuan0124 commented Jan 3, 2023

PR Details

Description

Related Issue

Motivation and Context

How Has This Been Tested?

Types of changes

  • Defect fix (non-breaking change that fixes an issue)
  • New feature (non-breaking change that adds functionality)
  • Breaking change (fix or feature that cause existing functionality to change)

Checklist:

  • I have added any new packages to the sonar-scanner.properties file
  • My change requires a change to the documentation.
  • I have updated the documentation accordingly.
  • I have read the CONTRIBUTING document.
    CARMA Contributing Guide
  • I have added tests to cover my changes.
  • All new and existing tests passed.


/*Lidar*/
if (!carla_lidar_stream_enabled) {
ROS_ERROR_STREAM("CARLA LIDAR data stream is disabled");
Copy link
Contributor

Choose a reason for hiding this comment

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

I think error is probably the wrong log level for this, debug seems more appropriate. Nothing has necessarily gone wrong if we've disabled the simulated LIDAR.

ROS_ERROR_STREAM("CARLA LIDAR data stream is disabled");
} else if (localization_stream_enabled && object_detection_stream_enabled) {
throw std::invalid_argument("CARLA LIDAR sensor and both ground truth data streams cannot be enabled at the same time");
} else {
Copy link
Contributor

Choose a reason for hiding this comment

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

Do we need a catch-all somewhere to check if we've got a minimal set of data to run with? If we turn off simulated lidar/gnss AND the localization truth data, we've got nothing to work with at all. I imagine CARMA Platform downstream of these nodes would complain in that case, but the error would be further away from the source than if we were to check that somewhere here.

ros::CARMANodeHandle::spin();
/*Camera*/
if (!carla_camera_stream_enabled) {
ROS_ERROR_STREAM("CARLA camera data stream is disabled");
Copy link
Contributor

Choose a reason for hiding this comment

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

Similar to above RE: debug level

/*Camera*/
if (!carla_camera_stream_enabled) {
ROS_ERROR_STREAM("CARLA camera data stream is disabled");
} else if (carla_camera_stream_enabled && object_detection_stream_enabled) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Minor: The check here again on carla_camera_stream_enabled is redundant and can be removed, since we're already in the else-branch of an if (!carla_camera_stream_enabled) ...

}
/*GNSS*/
if (!carla_gnss_stream_enabled) {
ROS_ERROR_STREAM("CARLA camera data stream is disabled");
Copy link
Contributor

Choose a reason for hiding this comment

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

debug log

/*GNSS*/
if (!carla_gnss_stream_enabled) {
ROS_ERROR_STREAM("CARLA camera data stream is disabled");
} else if (carla_gnss_stream_enabled && localization_stream_enabled) {
Copy link
Contributor

Choose a reason for hiding this comment

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

first logical term redundant

<arg name='loc_ground_truth_enabled' value="false"/>
<remap from="/gt_localization_stream" to="~loc_ground_truth_enabled"/>
<group if="$(eval loc_ground_truth_enabled == 'true')">
<group if="$(eval arg('localization_stream') == 'true')">
Copy link
Contributor

Choose a reason for hiding this comment

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

Is this really the right syntax? I'm a bit unfamiliar, but anything == true reads as weird to me. Is this doing raw string comparison instead of converting the arg into a boolean? I'd have to look through the launch files elsewhere to see if this pattern is used, or somewhere in the roslaunch docs.

Not a huge deal if it works, but just a bit weird.

@sonarcloud
Copy link

sonarcloud bot commented Feb 21, 2023

Kudos, SonarCloud Quality Gate passed!    Quality Gate passed

Bug A 0 Bugs
Vulnerability A 0 Vulnerabilities
Security Hotspot A 0 Security Hotspots
Code Smell A 0 Code Smells

No Coverage information No Coverage information
0.0% 0.0% Duplication

2 similar comments
@sonarcloud
Copy link

sonarcloud bot commented Feb 24, 2023

Kudos, SonarCloud Quality Gate passed!    Quality Gate passed

Bug A 0 Bugs
Vulnerability A 0 Vulnerabilities
Security Hotspot A 0 Security Hotspots
Code Smell A 0 Code Smells

No Coverage information No Coverage information
0.0% 0.0% Duplication

@sonarcloud
Copy link

sonarcloud bot commented Mar 6, 2023

Kudos, SonarCloud Quality Gate passed!    Quality Gate passed

Bug A 0 Bugs
Vulnerability A 0 Vulnerabilities
Security Hotspot A 0 Security Hotspots
Code Smell A 0 Code Smells

No Coverage information No Coverage information
0.0% 0.0% Duplication

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants