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
Open
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
the License.
-->

<!--
<!--
Example launch file for the CARLA Sensors Integration node
Loads parameters and configures logging for the node

Expand All @@ -24,7 +24,11 @@ Loads parameters and configures logging for the node
<launch>

<arg name='role_name' default='ego_vehicle'/>

<arg name='object_detection_stream' default="false"/>
<arg name="localization_stream" default="false"/>
<arg name="carla_lidar_stream" default="true"/>
<arg name="carla_camera_stream" default="true"/>
<arg name="carla_gnss_stream" default="true"/>

<remap from="points_raw" to="/hardware_interface/lidar/points_raw"/>
<remap from="image_raw" to="/hardware_interface/camera/image_raw"/>
Expand All @@ -33,47 +37,34 @@ Loads parameters and configures logging for the node
<remap from="camera_info" to="/hardware_interface/camera/camera_info"/>
<remap from="gnss_fix_fused" to="/hardware_interface/gnss_fix_fused"/>

<!-- data_stream_toggle -->

<!--
# localization #
Extract the pose, twist from carla odometry.
-->
<param name="localization_stream" value="false" type="bool"/>
<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="$(arg localization_stream)">
<node pkg='carma_carla_bridge' type='carla_to_carma_localization' name='carla_to_carma_localization' output='screen'>
<param name='role_name' type="str" value="$(arg role_name)"/>
<param name="localization_stream" value="true" type="bool"/>
</node>
</group>

<!--
# external objects
Extract the external objects from carla ObjectArray
-->
<param name="object_detection_stream" value="false" type="bool"/>
<arg name='obj_ground_truth_enabled' value="false"/>
<remap from="/gt_object_detection_stream" to="~obj_ground_truth_enabled"/>

<group if="$(eval obj_ground_truth_enabled == 'true')">
<group if="$(arg object_detection_stream)">
<node pkg='carma_carla_bridge' type='carla_to_carma_external_objects' name='carla_to_carma_external_objects' output='screen'>
<param name='role_name' type="str" value="$(arg role_name)"/>
<param name="object_detection_stream" value="true" type="bool"/>
</node>
</group>

<node pkg="carla_sensors_integration" type="carla_sensors_integration" name="carla_sensors_integration" output='screen'>
<param name='role_name' type="str" value="$(arg role_name)" />
<param name='object_detection_stream' type="bool" value="$(arg object_detection_stream)" />
<param name='localization_stream' type="bool" value="$(arg localization_stream)" />
<param name='carla_lidar_stream' type="bool" value="$(arg carla_lidar_stream)" />
<param name='carla_camera_stream' type="bool" value="$(arg carla_camera_stream)" />
<param name='carla_gnss_stream' type="bool" value="$(arg carla_gnss_stream)" />
</node>

<param name="carla_lidar_stream" value="true" type="bool"/>
<remap from="/carla_lidar" to="~carla_lidar_stream"/>
<param name="carla_camera_stream" value="true" type="bool"/>
<remap from="/carla_camera" to="~carla_camera_stream"/>
<param name="carla_gnss_stream" value="true" type="bool"/>
<remap from="/carla_gnss" to="~carla_gnss_stream"/>


<node name="carla_sensors_integration" pkg="carla_sensors_integration" type="carla_sensors_integration"/>


</launch>
</launch>
Original file line number Diff line number Diff line change
@@ -1,157 +1,130 @@
#include "carla_sensors_integration_node.h"

#include<ros/ros.h>

namespace carla_sensors
{
void CarlaSensorsNode::initialize()
namespace carla_sensors {
void CarlaSensorsNode::initialize() {
nh_.reset(new ros::CARMANodeHandle());
points_raw_pub_ = nh_ -> advertise < sensor_msgs::PointCloud2 > ("points_raw", 1);
image_raw_pub_ = nh_ -> advertise < sensor_msgs::Image > ("image_raw", 1);
image_color_pub_ = nh_ -> advertise < sensor_msgs::Image > ("image_color", 1);
image_rect_pub_ = nh_ -> advertise < sensor_msgs::Image > ("image_rect", 1);
camera_info_pub_ = nh_ -> advertise < sensor_msgs::CameraInfo > ("camera_info", 1);
gnss_fixed_fused_pub_ = nh_ -> advertise < gps_common::GPSFix > ("gnss_fix_fused", 1);

pnh_.reset(new ros::CARMANodeHandle("~"));
pnh_ -> getParam("role_name", carla_vehicle_role_);
pnh_ -> getParam("object_detection_stream", object_detection_stream_enabled);
pnh_ -> getParam("localization_stream", localization_stream_enabled);
pnh_ -> getParam("carla_lidar_stream", carla_lidar_stream_enabled);
pnh_ -> getParam("carla_camera_stream", carla_camera_stream_enabled);
pnh_ -> getParam("carla_gnss_stream", carla_gnss_stream_enabled);

if(!carla_lidar_stream_enabled && !carla_camera_stream_enabled && !carla_gnss_stream_enabled)
{
nh_.reset(new ros::CARMANodeHandle());
points_raw_pub_ = nh_->advertise<sensor_msgs::PointCloud2>("points_raw", 1);
image_raw_pub_= nh_->advertise<sensor_msgs::Image>("image_raw", 1);
image_color_pub_ = nh_->advertise<sensor_msgs::Image>("image_color",1);
image_rect_pub_ = nh_->advertise<sensor_msgs::Image>("image_rect", 1);
camera_info_pub_ = nh_->advertise<sensor_msgs::CameraInfo>("camera_info", 1);
gnss_fixed_fused_pub_ = nh_->advertise<gps_common::GPSFix>("gnss_fix_fused", 1);

pnh_.reset(new ros::CARMANodeHandle());
pnh_->getParam("role_name", carla_vehicle_role_);
pnh_->getParam("object_detection_stream", object_detection_stream_enabled);
pnh_->getParam("localization_stream", localization_stream_enabled);
pnh_->getParam("carla_lidar_stream", carla_lidar_stream_enabled);
pnh_->getParam("carla_camera_stream", carla_camera_stream_enabled);
pnh_->getParam("carla_gnss_stream", carla_gnss_stream_enabled);

//Subscribers

/*Lidar*/
if (!carla_lidar_stream_enabled)
{
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
{
point_cloud_sub_ = nh_->subscribe<sensor_msgs::PointCloud2>("/carla/" + carla_vehicle_role_ +"/lidar/lidar/point_cloud", 10, &CarlaSensorsNode::point_cloud_cb, this);
}

/*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)
{
throw std::invalid_argument("CARLA Camera sensor and ground truth object detection cannot be enabled at the same time");
}
else
{
image_raw_sub_ = nh_->subscribe<sensor_msgs::Image>("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/image", 10, &CarlaSensorsNode::image_raw_cb, this);
image_color_sub_ = nh_->subscribe<sensor_msgs::Image>("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/image_color", 10, &CarlaSensorsNode::image_color_cb, this);
image_rect_sub_ = nh_->subscribe<sensor_msgs::Image>("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/image_rect", 10, &CarlaSensorsNode::image_rect_cb, this);
}
/*GNSS*/
if (!carla_gnss_stream_enabled)
{
ROS_ERROR_STREAM("CARLA camera data stream is disabled");
}
else if (carla_gnss_stream_enabled && localization_stream_enabled)
{
throw std::invalid_argument("CARLA GNSS sensor and ground truth localization cannot be enabled at the same time");
}
else
{
gnss_fixed_fused_sub_ = nh_->subscribe<sensor_msgs::NavSatFix>("/carla/" + carla_vehicle_role_ + "/gnss/novatel_gnss/fix", 10, &CarlaSensorsNode::gnss_fixed_fused_cb, this);
}
camera_info_sub_ = nh_->subscribe<sensor_msgs::CameraInfo>("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/camera_info", 10, &CarlaSensorsNode::camera_info_cb, this);


ROS_ERROR_STREAM("Camera, Lidar and GNSS are disabled. Please make sure the configuration being set properly");
return;
}

void CarlaSensorsNode::run()
{
initialize();
ros::CARMANodeHandle::spin();
/*Lidar*/
if (!carla_lidar_stream_enabled) {
ROS_DEBUG_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.

point_cloud_sub_ = nh_ -> subscribe < sensor_msgs::PointCloud2 > ("/carla/" + carla_vehicle_role_ + "/lidar/lidar/point_cloud", 10, & CarlaSensorsNode::point_cloud_cb, this);
}

void CarlaSensorsNode::point_cloud_cb(sensor_msgs::PointCloud2 point_cloud)
{
if (point_cloud.data.size() == 0)
{
throw std::invalid_argument(" Invalid LIDAR Point Cloud Data");
exit(0);
}
if (point_cloud.header.stamp == point_cloud_msg.header.stamp && point_cloud_msg.header.seq != 0)
{
return;
}
/*Camera*/
if (!carla_camera_stream_enabled) {
ROS_DEBUG_STREAM("CARLA camera data stream is disabled");
} else if (object_detection_stream_enabled) {
throw std::invalid_argument("CARLA Camera sensor and ground truth object detection cannot be enabled at the same time");
} else {
image_raw_sub_ = nh_ -> subscribe < sensor_msgs::Image > ("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/image", 10, & CarlaSensorsNode::image_raw_cb, this);
image_color_sub_ = nh_ -> subscribe < sensor_msgs::Image > ("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/image_color", 10, & CarlaSensorsNode::image_color_cb, this);
image_rect_sub_ = nh_ -> subscribe < sensor_msgs::Image > ("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/image_rect", 10, & CarlaSensorsNode::image_rect_cb, this);
}
/*GNSS*/
if (!carla_gnss_stream_enabled) {
ROS_DEBUG_STREAM("CARLA camera data stream is disabled");
} else if (localization_stream_enabled) {
throw std::invalid_argument("CARLA GNSS sensor and ground truth localization cannot be enabled at the same time");
} else {
gnss_fixed_fused_sub_ = nh_ -> subscribe < sensor_msgs::NavSatFix > ("/carla/" + carla_vehicle_role_ + "/gnss/novatel_gnss/fix", 10, & CarlaSensorsNode::gnss_fixed_fused_cb, this);
}
camera_info_sub_ = nh_ -> subscribe < sensor_msgs::CameraInfo > ("/carla/" + carla_vehicle_role_ + "/camera/rgb/front/camera_info", 10, & CarlaSensorsNode::camera_info_cb, this);

carla_worker_.point_cloud_cb(point_cloud);
}

point_cloud_msg = carla_worker_.get_lidar_msg();
points_raw_pub_.publish(point_cloud_msg);
void CarlaSensorsNode::run() {
initialize();
ros::CARMANodeHandle::spin();
}

void CarlaSensorsNode::point_cloud_cb(sensor_msgs::PointCloud2 point_cloud) {
if (point_cloud.data.size() == 0) {
throw std::invalid_argument(" Invalid LIDAR Point Cloud Data");
exit(0);
}
if (point_cloud.header.stamp == point_cloud_msg.header.stamp && point_cloud_msg.header.seq != 0) {
return;
}

void CarlaSensorsNode::image_raw_cb(sensor_msgs::Image image_raw)
{
if (image_raw.data.size() == 0)
{
throw std::invalid_argument("Invalid image data");
}
carla_worker_.image_raw_cb(image_raw);
image_raw_msg = carla_worker_.get_image_raw_msg();
image_raw_pub_.publish(image_raw_msg);
carla_worker_.point_cloud_cb(point_cloud);

}
point_cloud_msg = carla_worker_.get_lidar_msg();
points_raw_pub_.publish(point_cloud_msg);

void CarlaSensorsNode::image_color_cb(sensor_msgs::Image image_color)
{
}

void CarlaSensorsNode::image_raw_cb(sensor_msgs::Image image_raw) {
if (image_raw.data.size() == 0) {
throw std::invalid_argument("Invalid image data");
}
carla_worker_.image_raw_cb(image_raw);
image_raw_msg = carla_worker_.get_image_raw_msg();
image_raw_pub_.publish(image_raw_msg);

if (image_color.data.size() == 0)
{
throw std::invalid_argument("Invalid image data");
}
}

carla_worker_.image_color_cb(image_color);
image_color_msg = carla_worker_.get_image_color_msg();
image_color_pub_.publish(image_color_msg);
void CarlaSensorsNode::image_color_cb(sensor_msgs::Image image_color) {

if (image_color.data.size() == 0) {
throw std::invalid_argument("Invalid image data");
}

void CarlaSensorsNode::image_rect_cb(sensor_msgs::Image image_rect)
{
if (image_rect.data.size() == 0)
{
throw std::invalid_argument("Invalid image data");
}
carla_worker_.image_color_cb(image_color);
image_color_msg = carla_worker_.get_image_color_msg();
image_color_pub_.publish(image_color_msg);

carla_worker_.image_rect_cb(image_rect);
image_rect_msg = carla_worker_.get_image_rect_msg();
image_rect_pub_.publish(image_rect_msg);
}

void CarlaSensorsNode::image_rect_cb(sensor_msgs::Image image_rect) {
if (image_rect.data.size() == 0) {
throw std::invalid_argument("Invalid image data");
}

void CarlaSensorsNode::camera_info_cb(sensor_msgs::CameraInfo camera_info)
{
carla_worker_.image_rect_cb(image_rect);
image_rect_msg = carla_worker_.get_image_rect_msg();
image_rect_pub_.publish(image_rect_msg);

carla_worker_.camera_info_cb(camera_info);
}

camera_info_msg = carla_worker_.get_camera_info();
camera_info_pub_.publish(camera_info_msg);
void CarlaSensorsNode::camera_info_cb(sensor_msgs::CameraInfo camera_info) {

}
carla_worker_.camera_info_cb(camera_info);

void CarlaSensorsNode::gnss_fixed_fused_cb(sensor_msgs::NavSatFix gnss_fixed)
{

camera_info_msg = carla_worker_.get_camera_info();
camera_info_pub_.publish(camera_info_msg);

carla_worker_.gnss_fixed_fused_cb(gnss_fixed);
gnss_fixed_msg = carla_worker_.get_gnss_fixed_msg();
gnss_fixed_fused_pub_.publish(gnss_fixed_msg);
}


}
}
void CarlaSensorsNode::gnss_fixed_fused_cb(sensor_msgs::NavSatFix gnss_fixed) {

carla_worker_.gnss_fixed_fused_cb(gnss_fixed);
gnss_fixed_msg = carla_worker_.get_gnss_fixed_msg();
gnss_fixed_fused_pub_.publish(gnss_fixed_msg);

}
}
16 changes: 0 additions & 16 deletions carma-carla-integration/carma-carla-agent/agent/bridge.launch
Original file line number Diff line number Diff line change
Expand Up @@ -76,21 +76,6 @@
#############################################
-->

<!--
# localization #
Extract the pose, twist from carla odometry.
-->
<node pkg='carma_carla_bridge' type='carla_to_carma_localization' name='carla_to_carma_localization' output='screen'>
<param name='role_name' type="str" value="$(arg role_name)"/>
</node>
<!--
# external objects
Extract the external objects from carla ObjectArray
-->>
<node pkg='carma_carla_bridge' type='carla_to_carma_external_objects' name='carla_to_carma_external_objects' output='screen'>
<param name='role_name' type="str" value="$(arg role_name)"/>
</node>

<!-- convert vehicle command to carla ackermann drive-->
<node pkg='carma_carla_bridge' type='carma_to_carla_ackermann_cmd' name='carma_to_carla_ackermann_cmd' output='screen'>
<param name='role_name' type="str" value="$(arg role_name)"/>
Expand Down Expand Up @@ -134,7 +119,6 @@
<param name='selected_plugins' type='str' value="$(arg selected_plugins)"/>
</node>


<!--
# guidance #
Set guidance to active once the plugins have been activated and the route has been selected.
Expand Down
Loading