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

Rerun examples #31

Merged
merged 3 commits into from
Feb 22, 2024
Merged
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
9 changes: 9 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,15 @@
## temporal vim files
*.sw*

##temporal files for rerun
blaze_face_short_range.tflite
face_landmarker.task
.pixi
noetic_ws
pixi.lock
indoor_forward_3_snapdragon_with_gt.bag


## files for html-slides
_site/
**/*.jekyll-cache
Expand Down
33 changes: 33 additions & 0 deletions rerun/examples/cpp-example-ros-bridge/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
# cpp-example-ros-bridge


## Installation
```
curl -fsSL https://pixi.sh/install.sh | bash
echo 'eval "$(pixi completion --shell bash)"' >> ~/.bashrc
#And then restart the shell or source the shell config file.
#rm ~/.pixi/bin/pixi

git clone [email protected]:rerun-io/cpp-example-ros-bridge.git
mv pixi.toml ..
mv rerun_bridge/ ..
rm -rf cpp-example-ros-bridge/

$HOME/.pixi/bin/./pixi run example
```

## some logs
```
$HOME/.pixi/bin/./pixi run example
✨ Pixi task (default): mkdir -p noetic_ws/src && ln -sfn $(pwd)/rerun_bridge noetic_ws/src/rerun_bridge
⠉ updating packages in 'default'
⠁ downloading [00:01:18] [━───────────────────] 21/542 ogre (+49) ⠁ linking [00:01:18] [━───────────────────] 21/542
```


## References
https://github.com/rerun-io/cpp-example-ros-bridge?tab=readme-ov-file
https://github.com/prefix-dev/pixi/



25 changes: 25 additions & 0 deletions rerun/examples/cpp-example-ros-bridge/pixi.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
[project]
name = "rerun_cpp_example_ros"
authors = ["rerun.io <[email protected]>"]
channels = ["robostack-staging", "conda-forge"]
description = "Use the Rerun C++ SDK together with ROS"
homepage = "https://rerun.io"
license = "Apache-2.0"
platforms = ["linux-64"]
repository = "https://github.com/rerun-io/cpp-example-ros"
version = "0.1.0"

[tasks]
ws = { cmd = "mkdir -p noetic_ws/src && ln -sfn $(pwd)/rerun_bridge noetic_ws/src/rerun_bridge", cwd = "." }
build = { cmd = "ls && catkin_make --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_EXPORT_COMPILE_COMMANDS=ON", depends_on = ["ws"], cwd = "noetic_ws"}
example_data = { cmd = "curl -L -C - -O http://rpg.ifi.uzh.ch/datasets/uzh-fpv-newer-versions/v3/indoor_forward_3_snapdragon_with_gt.bag", depends_on=["ws"], cwd = "noetic_ws/src/rerun_bridge"}
example = { cmd = "bash -c 'source ./devel/setup.bash && roslaunch rerun_bridge example.launch'", depends_on = [ "build", "example_data", "ws"], cwd = "noetic_ws" }

[dependencies]
compilers = ">=1.7.0,<1.8"
opencv = ">=4.9.0,<4.10"
ros-noetic-catkin = ">=0.8.10,<0.9"
ros-noetic-desktop = ">=1.5.0,<1.6"
ros-noetic-rosbag = ">=1.16.0,<1.17"
yaml-cpp = ">=0.8.0,<0.9"
rerun-sdk = ">=0.13.0,<0.14"
38 changes: 38 additions & 0 deletions rerun/examples/cpp-example-ros-bridge/rerun_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
cmake_minimum_required(VERSION 3.0.2)
project(rerun_bridge)

if(NOT DEFINED CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs nav_msgs cv_bridge)
find_package(OpenCV REQUIRED)
find_package(yaml-cpp REQUIRED)

include(FetchContent)
FetchContent_Declare(rerun_sdk URL https://github.com/rerun-io/rerun/releases/download/0.13.0/rerun_cpp_sdk.zip)
FetchContent_MakeAvailable(rerun_sdk)

include_directories(
include
${YAML_CPP_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)

catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS roscpp sensor_msgs nav_msgs cv_bridge
DEPENDS opencv yaml-cpp
)

add_library(${PROJECT_NAME} src/rerun_bridge/rerun_ros_interface.cpp)
add_executable(visualizer src/rerun_bridge/visualizer_node.cpp)

add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(visualizer ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBS} ${YAML_CPP_LIBRARIES} rerun_sdk)
target_link_libraries(visualizer ${PROJECT_NAME} ${catkin_LIBRARIES} ${YAML_CPP_LIBRARIES} rerun_sdk)

install(TARGETS visualizer DESTINATION bin)
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#pragma once

#include <geometry_msgs/PoseStamped.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/Imu.h>

#include <rerun.hpp>

void log_imu(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Imu::ConstPtr& msg
);

void log_image(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Image::ConstPtr& msg
);

void log_pose_stamped(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::PoseStamped::ConstPtr& msg
);

void log_odometry(
const rerun::RecordingStream& rec, const std::string& entity_path,
const nav_msgs::Odometry::ConstPtr& msg
);
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<launch>
<!-- Publishes the voxel grid to rviz for display -->
<node pkg="rosbag" type="play" name="player" args="-s 11.0 -u 47.0 -r 2.0 $(find rerun_bridge)/indoor_forward_3_snapdragon_with_gt.bag">
</node>

<!-- Run the logger node -->
<node name="rerun_bridge_node" pkg="rerun_bridge" type="visualizer" output="screen">
<rosparam param="yaml_path" subst_value="True">$(find rerun_bridge)/launch/example_params.yaml</rosparam>
</node>

</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
topic_to_entity_path:
/snappy_cam/stereo_l: /groundtruth/pose/snappy_cam/stereo_l
/snappy_cam/stereo_r: /groundtruth/pose/snappy_cam/stereo_r
extra_transform3ds:
- entity_path: /groundtruth/pose/snappy_cam/stereo_l
transform: [
-0.028228787368606456, -0.999601488301944, 1.2175294828553618e-05, 0.02172388268966517,
0.014401251861751119, -0.00041887083271471837, -0.9998962088597202, -6.605455433829172e-05,
0.999497743623523, -0.028225682131089447, 0.014407337010089172, -0.00048817563004522853,
0.0, 0.0, 0.0, 1.0
]
from_parent: true
- entity_path: /groundtruth/pose/snappy_cam/stereo_r
transform: [
-0.011823057800830705, -0.9998701444077991, -0.010950325390841398, -0.057904961033265645,
0.011552991631909482, 0.01081376681432078, -0.9998747875767439, 0.00043766687615362694,
0.9998633625093938, -0.011948086424720228, 0.011423639621249038, -0.00039944945687402214,
0.0, 0.0, 0.0, 1.0
]
from_parent: true
extra_pinholes:
- entity_path: /groundtruth/pose/snappy_cam/stereo_l
height: 480
width: 640
image_from_camera: [278.66723066149086, 0, 319.75221200593535, 0, 278.48991409740296, 241.96858910358173, 0, 0, 1]
- entity_path: /groundtruth/pose/snappy_cam/stereo_r
height: 480
width: 640
image_from_camera: [277.61640629770613, 0, 314.8944703346039, 0, 277.63749695723294, 236.04310050462587, 0, 0, 1]

15 changes: 15 additions & 0 deletions rerun/examples/cpp-example-ros-bridge/rerun_bridge/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<package format="2">
<name>rerun_bridge</name>
<version>0.1.0</version>
<description>The rerun_bridge package</description>
<maintainer email="[email protected]">rerun.io</maintainer>
<license>Apache-2.0</license>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>nav_msgs</depend>
<depend>cv_bridge</depend>
<depend>geometry_msgs</depend>
<depend>yaml-cpp</depend>
<buildtool_depend>catkin</buildtool_depend>
</package>
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
#pragma once

#include <opencv2/opencv.hpp>
#include <rerun.hpp>

// Adapters so we can borrow an OpenCV image easily into Rerun images without copying:
template <>
struct rerun::CollectionAdapter<uint8_t, cv::Mat> {
/// Borrow for non-temporary.
Collection<uint8_t> operator()(const cv::Mat& img) {
assert(
"OpenCV matrix was expected have bit depth CV_U8" && CV_MAT_DEPTH(img.type()) == CV_8U
);

return Collection<uint8_t>::borrow(img.data, img.total() * img.channels());
}

// Do a full copy for temporaries (otherwise the data might be deleted when the temporary is destroyed).
Collection<uint8_t> operator()(cv::Mat&& img) {
assert(
"OpenCV matrix was expected have bit depth CV_U8" && CV_MAT_DEPTH(img.type()) == CV_8U
);

std::vector<uint8_t> img_vec(img.total() * img.channels());
img_vec.assign(img.data, img.data + img.total() * img.channels());
return Collection<uint8_t>::take_ownership(std::move(img_vec));
}
};

inline rerun::Collection<rerun::TensorDimension> tensor_shape(const cv::Mat& img) {
return {img.rows, img.cols, img.channels()};
};
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
#include <cv_bridge/cv_bridge.h>
#include <geometry_msgs/PoseStamped.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/Imu.h>
#include <nav_msgs/Odometry.h>
#include <rerun.hpp>
#include <rerun_bridge/rerun_ros_interface.hpp>

#include "collection_adapters.hpp"

void log_imu(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Imu::ConstPtr& msg
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());

rec.log(entity_path + "/x", rerun::Scalar(msg->linear_acceleration.x));
rec.log(entity_path + "/y", rerun::Scalar(msg->linear_acceleration.y));
rec.log(entity_path + "/z", rerun::Scalar(msg->linear_acceleration.z));
}

void log_image(
const rerun::RecordingStream& rec, const std::string& entity_path,
const sensor_msgs::Image::ConstPtr& msg
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());

cv::Mat img = cv_bridge::toCvCopy(msg, "rgb8")->image;
rec.log(entity_path, rerun::Image(tensor_shape(img), rerun::TensorBuffer::u8(img)));
}

void log_pose_stamped(
const rerun::RecordingStream& rec, const std::string& entity_path,
const geometry_msgs::PoseStamped::ConstPtr& msg
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());

rec.log(
entity_path,
rerun::Transform3D(
rerun::Vector3D(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z),
rerun::Quaternion::from_wxyz(
msg->pose.orientation.w,
msg->pose.orientation.x,
msg->pose.orientation.y,
msg->pose.orientation.z
)
)
);

// this is a somewhat hacky way to get a trajectory visualization in Rerun
// this should be be easier in the future, see https://github.com/rerun-io/rerun/issues/723
std::string trajectory_entity_path = "/trajectories/" + entity_path;
rec.log(
trajectory_entity_path,
rerun::Points3D(
{{static_cast<float>(msg->pose.position.x),
static_cast<float>(msg->pose.position.y),
static_cast<float>(msg->pose.position.z)}}
)
);
}

void log_odometry(
const rerun::RecordingStream& rec, const std::string& entity_path,
const nav_msgs::Odometry::ConstPtr& msg
) {
rec.set_time_seconds("timestamp", msg->header.stamp.toSec());

rec.log(
entity_path,
rerun::Transform3D(
rerun::Vector3D(
msg->pose.pose.position.x,
msg->pose.pose.position.y,
msg->pose.pose.position.z
),
rerun::Quaternion::from_wxyz(
msg->pose.pose.orientation.w,
msg->pose.pose.orientation.x,
msg->pose.pose.orientation.y,
msg->pose.pose.orientation.z
)
)
);
}
Loading