Skip to content

Commit

Permalink
Manif refactor (#648)
Browse files Browse the repository at this point in the history
  • Loading branch information
rbridges12 authored Feb 16, 2024
1 parent 257b684 commit 831c73a
Show file tree
Hide file tree
Showing 24 changed files with 228 additions and 329 deletions.
4 changes: 4 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -8,3 +8,7 @@
url = https://dawn.googlesource.com/dawn
shallow = true
branch = chromium/6108
[submodule "deps/manif"]
path = deps/manif
url = https://github.com/artivis/manif.git
shallow = true
11 changes: 6 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -91,12 +91,12 @@ if (MROVER_BUILD_SIM)
find_package(glfw3 REQUIRED)

include(cmake/webgpu.cmake)

add_subdirectory(deps/glfw3webgpu)
add_subdirectory(deps/glfw3webgpu SYSTEM)
endif ()
find_package(OpenCV REQUIRED)
find_package(ZED QUIET)
find_package(Eigen3 REQUIRED)
add_subdirectory(deps/manif SYSTEM)
find_package(PkgConfig REQUIRED)
pkg_search_module(NetLink libnl-3.0)
pkg_search_module(NetLinkRoute libnl-route-3.0)
Expand Down Expand Up @@ -146,6 +146,7 @@ catkin_package()
## Libraries

mrover_add_library(lie src/util/lie/*.cpp src/util/lie)
target_link_libraries(lie PUBLIC manif)

## ESW

Expand Down Expand Up @@ -187,7 +188,7 @@ endif ()
## Perception

mrover_add_nodelet(tag_detector src/perception/tag_detector/*.cpp src/perception/tag_detector src/perception/tag_detector/pch.hpp)
mrover_nodelet_link_libraries(tag_detector opencv_core opencv_objdetect opencv_aruco opencv_imgproc opencv_highgui lie)
mrover_nodelet_link_libraries(tag_detector opencv_core opencv_objdetect opencv_aruco opencv_imgproc opencv_highgui lie manif)

if (CUDA_FOUND)
mrover_add_library(streaming src/esw/streaming/*.c* src/esw/streaming)
Expand All @@ -200,7 +201,7 @@ endif ()
if (ZED_FOUND)
mrover_add_nodelet(zed src/perception/zed_wrapper/*.c* src/perception/zed_wrapper src/perception/zed_wrapper/pch.hpp)
mrover_nodelet_include_directories(zed ${ZED_INCLUDE_DIRS} ${CUDA_INCLUDE_DIRS})
mrover_nodelet_link_libraries(zed ${ZED_LIBRARIES} ${SPECIAL_OS_LIBS} lie)
mrover_nodelet_link_libraries(zed ${ZED_LIBRARIES} ${SPECIAL_OS_LIBS} lie manif)
mrover_nodelet_defines(zed
ALLOW_BUILD_DEBUG # Ignore ZED warnings about Debug mode
__CUDA_INCLUDE_COMPILER_INTERNAL_HEADERS__ # Eigen includes some files it should not, ignore
Expand All @@ -216,7 +217,7 @@ mrover_add_node(arm_controller src/teleoperation/arm_controller/*.cpp)
if (MROVER_BUILD_SIM)
mrover_add_nodelet(simulator src/simulator/*.cpp src/simulator src/simulator/pch.hpp)
mrover_nodelet_include_directories(simulator ${ASSIMP_INCLUDE_DIRS} ${BULLET_INCLUDE_DIRS} ${OPENCV_INCLUDE_DIRS} src/simulator/imgui)
mrover_nodelet_link_libraries(simulator ${ASSIMP_LIBRARIES} ${BULLET_LIBRARIES} glfw3webgpu webgpu glfw opencv_core opencv_imgcodecs opencv_imgproc lie)
mrover_nodelet_link_libraries(simulator ${ASSIMP_LIBRARIES} ${BULLET_LIBRARIES} glfw3webgpu webgpu glfw opencv_core opencv_imgcodecs opencv_imgproc lie manif)
mrover_nodelet_defines(simulator BOOST_THREAD_PROVIDES_FUTURE)
endif ()

Expand Down
1 change: 1 addition & 0 deletions deps/manif
Submodule manif added at c8a9fc
3 changes: 2 additions & 1 deletion src/perception/tag_detector/pch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,5 +30,6 @@
#include <mrover/DetectorParamsConfig.h>

#include <loop_profiler.hpp>
#include <manif/manif.h>
#include <point.hpp>
#include <se3.hpp>
#include <lie.hpp>
2 changes: 1 addition & 1 deletion src/perception/tag_detector/tag_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,5 +140,5 @@ namespace mrover {
res.success = true;
return true;
}

} // namespace mrover
4 changes: 2 additions & 2 deletions src/perception/tag_detector/tag_detector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ namespace mrover {
int id = -1;
int hitCount = 0;
cv::Point2f imageCenter{};
std::optional<SE3> tagInCam;
std::optional<SE3d> tagInCam;
};

class TagDetectorNodelet : public nodelet::Nodelet {
Expand Down Expand Up @@ -53,7 +53,7 @@ namespace mrover {

void publishThresholdedImage();

std::optional<SE3> getTagInCamFromPixel(sensor_msgs::PointCloud2ConstPtr const& cloudPtr, size_t u, size_t v);
std::optional<SE3d> getTagInCamFromPixel(sensor_msgs::PointCloud2ConstPtr const& cloudPtr, size_t u, size_t v);

public:
TagDetectorNodelet() = default;
Expand Down
10 changes: 5 additions & 5 deletions src/perception/tag_detector/tag_detector.processing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ namespace mrover {
* @param u X Pixel Position
* @param v Y Pixel Position
*/
std::optional<SE3> TagDetectorNodelet::getTagInCamFromPixel(sensor_msgs::PointCloud2ConstPtr const& cloudPtr, size_t u, size_t v) {
std::optional<SE3d> TagDetectorNodelet::getTagInCamFromPixel(sensor_msgs::PointCloud2ConstPtr const& cloudPtr, size_t u, size_t v) {
assert(cloudPtr);

if (u >= cloudPtr->width || v >= cloudPtr->height) {
Expand All @@ -23,7 +23,7 @@ namespace mrover {
return std::nullopt;
}

return std::make_optional<SE3>(R3{point.x, point.y, point.z}, SO3{});
return std::make_optional<SE3d>(R3{point.x, point.y, point.z}, SO3d::Identity());
}

/**
Expand Down Expand Up @@ -81,7 +81,7 @@ namespace mrover {
if (tag.tagInCam) {
// Publish tag to immediate
std::string immediateFrameId = "immediateFiducial" + std::to_string(tag.id);
SE3::pushToTfTree(mTfBroadcaster, immediateFrameId, mCameraFrameId, tag.tagInCam.value());
SE3Conversions::pushToTfTree(mTfBroadcaster, immediateFrameId, mCameraFrameId, tag.tagInCam.value());
}
}

Expand All @@ -108,8 +108,8 @@ namespace mrover {
std::string immediateFrameId = "immediateFiducial" + std::to_string(tag.id);
// Publish tag to odom
std::string const& parentFrameId = mUseOdom ? mOdomFrameId : mMapFrameId;
SE3 tagInParent = SE3::fromTfTree(mTfBuffer, parentFrameId, immediateFrameId);
SE3::pushToTfTree(mTfBroadcaster, "fiducial" + std::to_string(id), parentFrameId, tagInParent);
SE3d tagInParent = SE3Conversions::fromTfTree(mTfBuffer, parentFrameId, immediateFrameId);
SE3Conversions::pushToTfTree(mTfBroadcaster, "fiducial" + std::to_string(id), parentFrameId, tagInParent);
} catch (tf2::ExtrapolationException const&) {
NODELET_WARN("Old data for immediate tag");
} catch (tf2::LookupException const&) {
Expand Down
3 changes: 1 addition & 2 deletions src/perception/zed_wrapper/pch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,5 @@
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>

#include <se3.hpp>
#include <point.hpp>
#include <loop_profiler.hpp>
#include <point.hpp>
1 change: 0 additions & 1 deletion src/perception/zed_wrapper/zed_wrapper.bridge.cu
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
// Be careful what you include in this file, it is compiled with nvcc (NVIDIA CUDA compiler)
// For example OpenCV and lie includes cause problems

#include "zed_wrapper.hpp"

Expand Down
13 changes: 8 additions & 5 deletions src/perception/zed_wrapper/zed_wrapper.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
#include "zed_wrapper.hpp"

#include <manif/manif.h>
#include <lie.hpp>

namespace mrover {

/**
Expand Down Expand Up @@ -252,11 +255,11 @@ namespace mrover {
sl::Translation const& translation = pose.getTranslation();
sl::Orientation const& orientation = pose.getOrientation();
try {
SE3 leftCameraInOdom{{translation.x, translation.y, translation.z},
Eigen::Quaterniond{orientation.w, orientation.x, orientation.y, orientation.z}.normalized()};
SE3 leftCameraInBaseLink = SE3::fromTfTree(mTfBuffer, "base_link", "zed2i_left_camera_frame");
SE3 baseLinkInOdom = leftCameraInBaseLink * leftCameraInOdom;
SE3::pushToTfTree(mTfBroadcaster, "base_link", "odom", baseLinkInOdom);
SE3d leftCameraInOdom{{translation.x, translation.y, translation.z},
Eigen::Quaterniond{orientation.w, orientation.x, orientation.y, orientation.z}.normalized()};
SE3d baseLinkToLeftCamera = SE3Conversions::fromTfTree(mTfBuffer, "base_link", "zed2i_left_camera_frame");
SE3d baseLinkInOdom = leftCameraInOdom * baseLinkToLeftCamera;
SE3Conversions::pushToTfTree(mTfBroadcaster, "base_link", "odom", baseLinkInOdom);
} catch (tf2::TransformException& e) {
NODELET_WARN_STREAM("Failed to get transform: " << e.what());
}
Expand Down
3 changes: 2 additions & 1 deletion src/simulator/pch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,10 @@

#include <bimap.hpp>
#include <loop_profiler.hpp>
#include <manif/manif.h>
#include <params_utils.hpp>
#include <point.hpp>
#include <se3.hpp>
#include <lie.hpp>
#include <units.hpp>

#include <mrover/ControllerState.h>
Expand Down
55 changes: 26 additions & 29 deletions src/simulator/simulator.controls.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,40 +82,37 @@ namespace mrover {
}

auto SimulatorNodelet::freeLook(Clock::duration dt) -> void {
float flySpeed = mFlySpeed * std::chrono::duration_cast<std::chrono::duration<float>>(dt).count();
if (glfwGetKey(mWindow.get(), mCamRightKey) == GLFW_PRESS) {
mCameraInWorld = SE3{R3{0, -flySpeed, 0}, SO3{}} * mCameraInWorld;
}
if (glfwGetKey(mWindow.get(), mCamLeftKey) == GLFW_PRESS) {
mCameraInWorld = SE3{R3{0, flySpeed, 0}, SO3{}} * mCameraInWorld;
}
if (glfwGetKey(mWindow.get(), mCamForwardKey) == GLFW_PRESS) {
mCameraInWorld = SE3{R3{flySpeed, 0, 0}, SO3{}} * mCameraInWorld;
}
if (glfwGetKey(mWindow.get(), mCamBackwardKey) == GLFW_PRESS) {
mCameraInWorld = SE3{R3{-flySpeed, 0, 0}, SO3{}} * mCameraInWorld;
}
if (glfwGetKey(mWindow.get(), mCamUpKey) == GLFW_PRESS) {
mCameraInWorld = mCameraInWorld * SE3{R3{0, 0, flySpeed}, SO3{}};
}
if (glfwGetKey(mWindow.get(), mCamDownKey) == GLFW_PRESS) {
mCameraInWorld = mCameraInWorld * SE3{R3{0, 0, -flySpeed}, SO3{}};
}
auto axis = [this](int positive, int negative) -> double {
return (glfwGetKey(mWindow.get(), positive) == GLFW_PRESS) - (glfwGetKey(mWindow.get(), negative) == GLFW_PRESS);
};

Eigen::Vector2i size;
glfwGetWindowSize(mWindow.get(), &size.x(), &size.y());

Eigen::Vector2d center = (size / 2).cast<double>();
float flySpeed = mFlySpeed * std::chrono::duration_cast<std::chrono::duration<float>>(dt).count();
R3 keyDelta = R3{axis(mCamForwardKey, mCamBackwardKey), axis(mCamLeftKey, mCamRightKey), axis(mCamUpKey, mCamDownKey)} * flySpeed;

Eigen::Vector2i windowSize;
glfwGetWindowSize(mWindow.get(), &windowSize.x(), &windowSize.y());
Eigen::Vector2d windowCenter = (windowSize / 2).cast<double>();
Eigen::Vector2d mouse;
glfwGetCursorPos(mWindow.get(), &mouse.x(), &mouse.y());
Eigen::Vector2d mouseDelta = (mouse - windowCenter) * mLookSense;

SE3d::Tangent cameraRelativeTwist;
cameraRelativeTwist << keyDelta.x(), keyDelta.y(), 0.0, 0.0, mouseDelta.y(), 0.0;

SE3d::Tangent worldRelativeTwist;
worldRelativeTwist << 0.0, 0.0, keyDelta.z(), 0.0, 0.0, 0.0;

// The plus operator is overloaded and corresponds to lplus and rplus in the micro Lie paper
// It applies the exponential map to the tangent space element
// The result can be acted upon a group element (in this case SE3)
// The side of the plus operator determines word vs. camera space application
mCameraInWorld = worldRelativeTwist + mCameraInWorld + cameraRelativeTwist;

Eigen::Vector2d delta = (mouse - center) * mLookSense;
SO3d::Tangent worldRelativeAngularVelocity;
worldRelativeAngularVelocity << 0.0, 0.0, -mouseDelta.x();

// TODO(quintin): use lie algebra more here? we have a perturbation in the tangent space
R3 p = mCameraInWorld.position();
SO3 q = SO3{delta.y(), R3::UnitY()} * mCameraInWorld.rotation() * SO3{-delta.x(), R3::UnitZ()};
mCameraInWorld = SE3{p, q};
// TODO: Is there a way to combine this with the above?
mCameraInWorld.asSO3() = worldRelativeAngularVelocity + mCameraInWorld.asSO3();

centerCursor();
}
Expand Down Expand Up @@ -160,4 +157,4 @@ namespace mrover {
}
}

} // namespace mrover
} // namespace mrover
10 changes: 5 additions & 5 deletions src/simulator/simulator.gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,15 +94,15 @@ namespace mrover {
URDF const& rover = it->second;

{
SE3 baseLinkInMap = rover.linkInWorld("base_link");
R3 p = baseLinkInMap.position();
S3 q = baseLinkInMap.rotation().quaternion();
SE3d baseLinkInMap = rover.linkInWorld("base_link");
R3 p = baseLinkInMap.translation();
S3 q = baseLinkInMap.quat();
ImGui::Text("Rover Position: (%.2f, %.2f, %.2f)", p.x(), p.y(), p.z());
ImGui::Text("Rover Orientation: (%.2f, %.2f, %.2f, %.2f)", q.w(), q.x(), q.y(), q.z());
}
{
R3 p = mCameraInWorld.position();
S3 q = mCameraInWorld.rotation().quaternion();
R3 p = mCameraInWorld.translation();
S3 q = mCameraInWorld.quat();
ImGui::Text("Camera Position: (%.2f, %.2f, %.2f)", p.x(), p.y(), p.z());
ImGui::Text("Camera Orientation: (%.2f, %.2f, %.2f, %.2f)", q.w(), q.x(), q.y(), q.z());
}
Expand Down
6 changes: 3 additions & 3 deletions src/simulator/simulator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ namespace mrover {

auto makeCameraForLink(SimulatorNodelet& simulator, btMultibodyLink const* link) -> Camera;

[[nodiscard]] auto linkInWorld(std::string const& linkName) const -> SE3;
[[nodiscard]] auto linkInWorld(std::string const& linkName) const -> SE3d;
};

struct PeriodicTask {
Expand Down Expand Up @@ -305,7 +305,7 @@ namespace mrover {

auto getUrdf(std::string const& name) -> std::optional<std::reference_wrapper<URDF>>;

SE3 mCameraInWorld{R3{-3.0, 0.0, 1.5}, SO3{}};
SE3d mCameraInWorld{R3{-3.0, 0.0, 1.5}, SO3d::Identity()};

std::vector<StereoCamera> mStereoCameras;
std::vector<Camera> mCameras;
Expand Down Expand Up @@ -432,7 +432,7 @@ namespace mrover {

auto urdfPoseToBtTransform(urdf::Pose const& pose) -> btTransform;

auto btTransformToSe3(btTransform const& transform) -> SE3;
auto btTransformToSe3(btTransform const& transform) -> SE3d;

auto computeCameraToClip(float fovY, float aspect, float zNear, float zFar) -> Eigen::Matrix4f;

Expand Down
20 changes: 11 additions & 9 deletions src/simulator/simulator.physics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,12 @@

namespace mrover {

auto btTransformToSe3(btTransform const& transform) -> SE3 {
auto btTransformToSe3(btTransform const& transform) -> SE3d {
btVector3 const& p = transform.getOrigin();
btQuaternion const& q = transform.getRotation();
return SE3{R3{p.x(), p.y(), p.z()}, SO3{q.w(), q.x(), q.y(), q.z()}};
// Note: Must convert the Bullet quaternion (floats) to a normalized Eigen quaternion (doubles).
// Otherwise the normality check will fail in the SO3 constructor.
return SE3d{R3{p.x(), p.y(), p.z()}, Eigen::Quaterniond{q.w(), q.x(), q.y(), q.z()}.normalized()};
}

auto SimulatorNodelet::initPhysics() -> void {
Expand Down Expand Up @@ -76,9 +78,9 @@ namespace mrover {
int index = urdf.linkNameToMeta.at(link->name).index;
// TODO(quintin): figure out why we need to negate rvector
btTransform parentToChild{urdf.physics->getParentToLocalRot(index), -urdf.physics->getRVector(index)};
SE3 childInParent = btTransformToSe3(parentToChild.inverse());
SE3d childInParent = btTransformToSe3(parentToChild.inverse());

SE3::pushToTfTree(mTfBroadcaster, link->name, link->getParent()->name, childInParent);
SE3Conversions::pushToTfTree(mTfBroadcaster, link->name, link->getParent()->name, childInParent);
}

for (urdf::JointSharedPtr const& child_joint: link->child_joints) {
Expand All @@ -95,17 +97,17 @@ namespace mrover {
if (auto modelOpt = getUrdf(modelName)) {
URDF const& model = *modelOpt;

SE3 modelInMap = btTransformToSe3(model.physics->getBaseWorldTransform());
SE3 roverInMap = btTransformToSe3(rover.physics->getBaseWorldTransform());
SE3d modelInMap = btTransformToSe3(model.physics->getBaseWorldTransform());
SE3d roverInMap = btTransformToSe3(rover.physics->getBaseWorldTransform());

R3 roverToModel = modelInMap.position() - roverInMap.position();
R3 roverToModel = modelInMap.translation() - roverInMap.translation();
double roverDistanceToModel = roverToModel.norm();
roverToModel /= roverDistanceToModel;
R3 roverForward = roverInMap.rotation().matrix().col(0);
double roverDotModel = roverToModel.dot(roverForward);

if (roverDotModel > 0 && roverDistanceToModel < threshold) {
SE3::pushToTfTree(mTfBroadcaster, modelName, "map", modelInMap);
SE3Conversions::pushToTfTree(mTfBroadcaster, modelName, "map", modelInMap);
}
}
};
Expand All @@ -115,7 +117,7 @@ namespace mrover {
}
}

auto URDF::linkInWorld(std::string const& linkName) const -> SE3 {
auto URDF::linkInWorld(std::string const& linkName) const -> SE3d {
int index = linkNameToMeta.at(linkName).index;
return btTransformToSe3(index == -1 ? physics->getBaseWorldTransform() : physics->getLink(index).m_cachedWorldTransform);
}
Expand Down
Loading

0 comments on commit 831c73a

Please sign in to comment.