Skip to content

Commit

Permalink
Fixed topic names for ZED wrapper and Sim (#19)
Browse files Browse the repository at this point in the history
* ZED Naming conflicts

* OD in the sim and on ZED

* style

* style
  • Loading branch information
jbrhm authored Oct 1, 2024
1 parent 33d94d6 commit 2bb7799
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion perception/object_detector/object_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace mrover {
}

StereoObjectDetector::StereoObjectDetector() {
mSensorSub = create_subscription<sensor_msgs::msg::PointCloud2>("/camera/left/points", 1, [this](sensor_msgs::msg::PointCloud2::UniquePtr const& msg) {
mSensorSub = create_subscription<sensor_msgs::msg::PointCloud2>("/zed/left/points", 1, [this](sensor_msgs::msg::PointCloud2::UniquePtr const& msg) {
StereoObjectDetector::pointCloudCallback(msg);
});
}
Expand Down
10 changes: 5 additions & 5 deletions perception/zed_wrapper/zed_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,13 @@ namespace mrover {
RCLCPP_INFO(this->get_logger(), "Created Zed Wrapper Node, %s", NODE_NAME);

// Publishers
mRightImgPub = create_publisher<sensor_msgs::msg::Image>("right/image", 1);
mLeftImgPub = create_publisher<sensor_msgs::msg::Image>("left/image", 1);
mRightImgPub = create_publisher<sensor_msgs::msg::Image>("zed/right/image", 1);
mLeftImgPub = create_publisher<sensor_msgs::msg::Image>("zed/left/image", 1);
mImuPub = create_publisher<sensor_msgs::msg::Imu>("zed_imu/data_raw", 1);
mMagPub = create_publisher<sensor_msgs::msg::MagneticField>("zed_imu/mag", 1);
mPcPub = create_publisher<sensor_msgs::msg::PointCloud2>("camera/left/points", 1);
mRightCamInfoPub = create_publisher<sensor_msgs::msg::CameraInfo>("camera/right/camera_info", 1);
mLeftCamInfoPub = create_publisher<sensor_msgs::msg::CameraInfo>("camera/left/camera_info", 1);
mPcPub = create_publisher<sensor_msgs::msg::PointCloud2>("zed/left/points", 1);
mRightCamInfoPub = create_publisher<sensor_msgs::msg::CameraInfo>("zed/right/camera_info", 1);
mLeftCamInfoPub = create_publisher<sensor_msgs::msg::CameraInfo>("zed/left/camera_info", 1);

// Declare and set Params
int imageWidth{};
Expand Down
2 changes: 1 addition & 1 deletion scripts/visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ def paintEvent(self, event):
self.resize(self.renderer.defaultSize())
self.renderer.render(painter)

def update(self):
def update(self): # type: ignore[override]
rclpy.spin_once(self.viz)
with self.state_machine.mutex:
if self.graph is None or self.state_machine.needs_redraw:
Expand Down

0 comments on commit 2bb7799

Please sign in to comment.