Skip to content

Commit

Permalink
Added missing dependencies (#617)
Browse files Browse the repository at this point in the history
* Added missing dependencies

* Fixed cmake format
  • Loading branch information
joel-mb committed Jul 21, 2022
1 parent 1604eb5 commit 4f52fe6
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 4 deletions.
3 changes: 2 additions & 1 deletion pcl_recorder/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ elseif(${ROS_VERSION} EQUAL 2)
find_package(rclcpp_components REQUIRED)
find_package(sensor_msgs COMPONENTS)
find_package(tf2 REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(pcl_conversions REQUIRED)
Expand All @@ -65,7 +66,7 @@ elseif(${ROS_VERSION} EQUAL 2)
add_executable(${PROJECT_NAME}_node src/PclRecorderROS2.cpp src/mainROS2.cpp)

ament_target_dependencies(${PROJECT_NAME}_node rclcpp sensor_msgs
pcl_conversions tf2_ros tf2)
pcl_conversions tf2 tf2_ros)

target_link_libraries(${PROJECT_NAME}_node ${Boost_SYSTEM_LIBRARY}
${PCL_LIBRARIES})
Expand Down
4 changes: 2 additions & 2 deletions pcl_recorder/src/PclRecorderROS2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ PclRecorderROS2::PclRecorderROS2() : Node("pcl_recorder")
roleName = "ego_vehicle";
}
auto sub_opt = rclcpp::SubscriptionOptions();
sub_opt.callback_group = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
sub_opt.callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
sub = this->create_subscription<sensor_msgs::msg::PointCloud2>("/carla/" + roleName + "/lidar", 10, std::bind(&PclRecorderROS2::callback, this, std::placeholders::_1), sub_opt);
}

Expand All @@ -47,7 +47,7 @@ void PclRecorderROS2::callback(const sensor_msgs::msg::PointCloud2::SharedPtr cl

Eigen::Affine3d transform;
try {
transform = tf2::transformToEigen (tf_buffer_->lookupTransform(fixed_frame_, cloud->header.frame_id, cloud->header.stamp, rclcpp::Duration(1)));
transform = tf2::transformToEigen (tf_buffer_->lookupTransform(fixed_frame_, cloud->header.frame_id, cloud->header.stamp, rclcpp::Duration::from_seconds(1)));

pcl::PointCloud<pcl::PointXYZ> pclCloud;
pcl::fromROSMsg(*cloud, pclCloud);
Expand Down
2 changes: 1 addition & 1 deletion rviz_carla_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ elseif(${ROS_VERSION} EQUAL 2)
plugin_description_ros2.xml)

ament_target_dependencies(rviz_carla_plugin rclcpp carla_msgs nav_msgs
carla_ros_scenario_runner_types)
carla_ros_scenario_runner_types rviz_common)

ament_export_libraries(${PROJECT_NAME})

Expand Down

0 comments on commit 4f52fe6

Please sign in to comment.