-
-
Notifications
You must be signed in to change notification settings - Fork 4.5k
fix(ros2): move ROS2 unregistration before actor deregistration #9640
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
Closed
youtalk
wants to merge
17
commits into
carla-simulator:ue5-dev
from
youtalk:fix/ros2-multigpu-actor-destroy
Closed
Changes from 1 commit
Commits
Show all changes
17 commits
Select commit
Hold shift + click to select a range
dbceaf9
feat(ros2): add template infrastructure for publisher/subscriber system
youtalk 4196586
feat(ros2): add unified camera publisher base class
youtalk 5827f51
feat(ros2): migrate non-camera publishers to PublisherImpl templates
youtalk eb6f0a5
feat(ros2): remove obsolete listener wrapper classes
youtalk faff233
feat(ros2): refactor subscribers and add Ackermann control types
youtalk 7aefb07
feat(ros2): overhaul ROS2 manager with actor-based registration
youtalk 1e2fba9
feat(ros2): update Unreal plugin for new ROS2 registration API
youtalk 32b2da9
fix(ros2): separate cd3d640f3 refactor from 201d375d3 multi-GPU fix
youtalk fee14f4
feat(ros2): add ROS2 native example scripts and update build system
youtalk 99b7fa4
fix(ros2): adapt build system for refactored ROS2 publishers
youtalk b89e02f
Update CHANGELOG with recent fixes and ROS2 refactor
youtalk 0b1fd3e
Update PythonAPI/examples/ros2/README.md
youtalk 109a85a
fix(ros2): address Copilot review comments on PR #9638
youtalk 0fd77f3
fix(ros2): correct PointField datatypes in CarlaDVSPublisher
youtalk e603bd7
revert
youtalk 23a892e
fix(ros2): move ROS2 unregistration before actor deregistration
youtalk 03d1408
Merge branch 'ue5-dev' into fix/ros2-multigpu-actor-destroy
youtalk File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
feat(ros2): add unified camera publisher base class
Introduce CarlaCameraPublisher as an abstract base class that manages Image and CameraInfo via two PublisherImpl<T> instances. Migrate CarlaRGBCameraPublisher to a thin subclass providing channel count and encoding. Replace CarlaDepthCameraPublisher, CarlaNormalsCameraPublisher, CarlaOpticalFlowCameraPublisher, CarlaSSCameraPublisher, and CarlaISCameraPublisher with type aliases to CarlaRGBCameraPublisher, eliminating ~2800 lines of duplicated boilerplate. Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp>
- Loading branch information
commit 419658678e1333bf5a917c2c78610b2dc520859f
There are no files selected for viewing
63 changes: 63 additions & 0 deletions
63
LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.cpp
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,63 @@ | ||
| // Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). | ||
| // This work is licensed under the terms of the MIT license. | ||
| // For a copy, see <https://opensource.org/licenses/MIT>. | ||
|
|
||
| #include "CarlaCameraPublisher.h" | ||
|
|
||
| namespace carla { | ||
| namespace ros2 { | ||
|
|
||
| std::vector<uint8_t> CarlaCameraPublisher::ComputeImage(uint32_t height, uint32_t width, const uint8_t *data) { | ||
| const size_t size = height * width * this->GetChannels() * sizeof(uint8_t); | ||
| std::vector<uint8_t> vector_data(data, data + size); | ||
| return vector_data; | ||
| } | ||
|
|
||
| bool CarlaCameraPublisher::WriteCameraInfo(int32_t seconds, uint32_t nanoseconds, uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify) { | ||
|
|
||
| _impl_camera_info->GetMessage()->header().stamp().sec(seconds); | ||
| _impl_camera_info->GetMessage()->header().stamp().nanosec(nanoseconds); | ||
| _impl_camera_info->GetMessage()->header().frame_id(GetFrameId()); | ||
|
|
||
| const double cx = static_cast<double>(width) / 2.0; | ||
| const double cy = static_cast<double>(height) / 2.0; | ||
| const double fx = static_cast<double>(width) / (2.0 * std::tan(fov) * M_PI / 360.0); | ||
| const double fy = fx; | ||
|
|
||
| _impl_camera_info->GetMessage()->height(height); | ||
| _impl_camera_info->GetMessage()->width(width); | ||
| _impl_camera_info->GetMessage()->distortion_model("plumb_bob"); | ||
| _impl_camera_info->GetMessage()->D({ 0.0, 0.0, 0.0, 0.0, 0.0 }); | ||
| _impl_camera_info->GetMessage()->k({fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0}); | ||
| _impl_camera_info->GetMessage()->r({ 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 }); | ||
| _impl_camera_info->GetMessage()->p({fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0}); | ||
| _impl_camera_info->GetMessage()->binning_x(0); | ||
| _impl_camera_info->GetMessage()->binning_y(0); | ||
|
|
||
| _impl_camera_info->GetMessage()->roi().x_offset(x_offset); | ||
| _impl_camera_info->GetMessage()->roi().y_offset(y_offset); | ||
| _impl_camera_info->GetMessage()->roi().height(height); | ||
| _impl_camera_info->GetMessage()->roi().width(width); | ||
| _impl_camera_info->GetMessage()->roi().do_rectify(do_rectify); | ||
|
|
||
| return true; | ||
| } | ||
|
|
||
| bool CarlaCameraPublisher::WriteImage(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, std::vector<uint8_t> data) { | ||
| _impl_image->GetMessage()->header().stamp().sec(seconds); | ||
| _impl_image->GetMessage()->header().stamp().nanosec(nanoseconds); | ||
| _impl_image->GetMessage()->header().frame_id(this->GetFrameId()); | ||
|
|
||
| _impl_image->GetMessage()->width(width); | ||
| _impl_image->GetMessage()->height(height); | ||
| _impl_image->GetMessage()->encoding(this->GetEncoding()); | ||
| _impl_image->GetMessage()->is_bigendian(0); | ||
| _impl_image->GetMessage()->step(width * this->GetChannels() * sizeof(uint8_t)); | ||
|
|
||
| _impl_image->GetMessage()->data(std::move(data)); // https://github.com/eProsima/Fast-DDS/issues/2330 | ||
|
|
||
| return true; | ||
| } | ||
|
|
||
| } // namespace ros2 | ||
| } // namespace carla | ||
64 changes: 64 additions & 0 deletions
64
LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.h
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,64 @@ | ||
| // Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). | ||
| // This work is licensed under the terms of the MIT license. | ||
| // For a copy, see <https://opensource.org/licenses/MIT>. | ||
|
|
||
| #pragma once | ||
|
|
||
| #include <memory> | ||
| #include <vector> | ||
|
|
||
| #include "carla/ros2/publishers/BasePublisher.h" | ||
| #include "carla/ros2/publishers/PublisherImpl.h" | ||
|
|
||
| #include "carla/ros2/types/Image.h" | ||
| #include "carla/ros2/types/ImagePubSubTypes.h" | ||
| #include "carla/ros2/types/CameraInfo.h" | ||
| #include "carla/ros2/types/CameraInfoPubSubTypes.h" | ||
|
|
||
| namespace carla { | ||
| namespace ros2 { | ||
|
|
||
| class CarlaCameraPublisher : public BasePublisher { | ||
| public: | ||
| struct ImageMsgTraits { | ||
| using msg_type = sensor_msgs::msg::Image; | ||
| using msg_pubsub_type = sensor_msgs::msg::ImagePubSubType; | ||
| }; | ||
|
|
||
| struct CameraInfoMsgTraits { | ||
| using msg_type = sensor_msgs::msg::CameraInfo; | ||
| using msg_pubsub_type = sensor_msgs::msg::CameraInfoPubSubType; | ||
| }; | ||
|
|
||
| CarlaCameraPublisher(std::string base_topic_name, std::string frame_id) : | ||
| BasePublisher(base_topic_name, frame_id), | ||
| _impl_image(std::make_shared<PublisherImpl<ImageMsgTraits>>()), | ||
| _impl_camera_info(std::make_shared<PublisherImpl<CameraInfoMsgTraits>>()) { | ||
| _impl_image->Init(GetBaseTopicName() + "/image"); | ||
| _impl_camera_info->Init(GetBaseTopicName() + "/camera_info"); | ||
| } | ||
|
|
||
| virtual uint8_t GetChannels() = 0; | ||
|
|
||
| bool Publish() { | ||
| return _impl_camera_info->Publish() && _impl_image->Publish(); | ||
| } | ||
|
|
||
| bool WriteCameraInfo(int32_t seconds, uint32_t nanoseconds, uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify); | ||
| bool WriteImage(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, const uint8_t* data) { | ||
| return WriteImage(seconds, nanoseconds, height, width, ComputeImage(height, width, data)); | ||
| } | ||
| bool WriteImage(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, std::vector<uint8_t> data); | ||
|
|
||
| private: | ||
| virtual std::string GetEncoding() = 0; | ||
|
|
||
| virtual std::vector<uint8_t> ComputeImage(uint32_t height, uint32_t width, const uint8_t* data); | ||
|
|
||
| private: | ||
| std::shared_ptr<PublisherImpl<ImageMsgTraits>> _impl_image; | ||
| std::shared_ptr<PublisherImpl<CameraInfoMsgTraits>> _impl_camera_info; | ||
| }; | ||
|
|
||
| } // namespace ros2 | ||
| } // namespace carla |
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
CameraInfo focal length computation uses
std::tan(fov)and then multiplies byM_PI/360. Sincefovis in degrees (from the sensor header), this computes tan() on degrees rather than radians and yields incorrect fx/fy (e.g., fov=90 gives near-zero fx). Use the same conversion used elsewhere in the codebase:std::tan(fov * M_PI / 360.0)inside tan().