diff --git a/README.md b/README.md index 3908121b1..de613922d 100644 --- a/README.md +++ b/README.md @@ -1,14 +1,16 @@ # fuse -**NOTE**: The `rolling` branch is a [work in progress](https://github.com/locusrobotics/fuse/issues/276) port of the fuse stack to ROS 2, it is **not** expected to work until said work is done! +Welcome to PickNik Robotics's fork of fuse! -The fuse stack provides a general architecture for performing sensor fusion live on a robot. Some possible applications -include state estimation, localization, mapping, and calibration. +## Getting Started + +Using the Dockerfile is the easiest way to get started. Once inside, simply `rosdep update` and `colcon build` and you're ready to get started! Try `ros2 launch fuse_tutorials fuse_3d_tutorial.launch.py` and look at its pertinent code for a crash course in fuse and its capabilities. ## Overview -fuse is a ROS framework for performing sensor fusion using nonlinear least squares optimization techniques. In -particular, fuse provides: +The fuse stack provides a general architecture for performing sensor fusion live on a robot using nonlinear least squares optimization techniques. +Some possible applications include state estimation, localization, mapping, and calibration. +In particular, fuse provides: * a plugin-based system for modeling sensor measurements * a similar plugin-based system for motion models diff --git a/fuse_constraints/include/fuse_constraints/marginalize_variables.hpp b/fuse_constraints/include/fuse_constraints/marginalize_variables.hpp index 6911376e6..f69c9aad4 100644 --- a/fuse_constraints/include/fuse_constraints/marginalize_variables.hpp +++ b/fuse_constraints/include/fuse_constraints/marginalize_variables.hpp @@ -36,10 +36,7 @@ #include -#include #include -#include -#include #include #include diff --git a/fuse_core/include/fuse_core/fuse_macros.hpp b/fuse_core/include/fuse_core/fuse_macros.hpp index 6484d12f3..be86909be 100644 --- a/fuse_core/include/fuse_core/fuse_macros.hpp +++ b/fuse_core/include/fuse_core/fuse_macros.hpp @@ -58,10 +58,6 @@ // Required by __MAKE_SHARED_ALIGNED_DEFINITION, that uses Eigen::aligned_allocator(). #include -#include -#include -#include - /** * Creates a custom new() implementation that ensures memory is allocated with proper byte * alignment. This should be added to the public section of classes or structs that contain diff --git a/fuse_core/include/fuse_core/transaction.hpp b/fuse_core/include/fuse_core/transaction.hpp index 4449c439d..9651d35bc 100644 --- a/fuse_core/include/fuse_core/transaction.hpp +++ b/fuse_core/include/fuse_core/transaction.hpp @@ -111,7 +111,7 @@ class Transaction /** * @brief Read-only access to this transaction's timestamp */ - const rclcpp::Time& stamp() const + [[nodiscard]] const rclcpp::Time& stamp() const { return stamp_; } @@ -129,7 +129,7 @@ class Transaction * * @return An iterator range containing all involved timestamps, ordered oldest to newest */ - const_stamp_range involvedStamps() const + [[nodiscard]] const_stamp_range involvedStamps() const { return involved_stamps_; } @@ -140,7 +140,7 @@ class Transaction * * @return The minimum (oldest) timestamp. */ - const rclcpp::Time& minStamp() const; + [[nodiscard]] const rclcpp::Time& minStamp() const; /** * @brief Read-only access to the maximum (newest) timestamp among the transaction's stamp and all @@ -148,21 +148,21 @@ class Transaction * * @return The maximum (newest) timestamp. */ - const rclcpp::Time& maxStamp() const; + [[nodiscard]] const rclcpp::Time& maxStamp() const; /** * @brief Read-only access to the added constraints * * @return An iterator range containing all added constraints */ - const_constraint_range addedConstraints() const; + [[nodiscard]] const_constraint_range addedConstraints() const; /** * @brief Read-only access to the removed constraints * * @return An iterator range containing all removed constraint UUIDs */ - const_uuid_range removedConstraints() const + [[nodiscard]] const_uuid_range removedConstraints() const { return removed_constraints_; } @@ -172,14 +172,14 @@ class Transaction * * @return An iterator range containing all added variables */ - const_variable_range addedVariables() const; + [[nodiscard]] const_variable_range addedVariables() const; /** * @brief Read-only access to the removed variables * * @return An iterator range containing all removed variable UUIDs */ - const_uuid_range removedVariables() const + [[nodiscard]] const_uuid_range removedVariables() const { return removed_variables_; } @@ -190,7 +190,7 @@ class Transaction * * @return True if the transaction is empty, false otherwise */ - bool empty() const; + [[nodiscard]] bool empty() const; /** * @brief Add a timestamp to the "involved stamps" collection @@ -275,7 +275,7 @@ class Transaction * * @return A unique pointer to a new instance of the most-derived Variable */ - Transaction::UniquePtr clone() const; + [[nodiscard]] Transaction::UniquePtr clone() const; /** * @brief Serialize this Constraint into the provided binary archive diff --git a/fuse_models/include/fuse_models/odometry_3d_publisher.hpp b/fuse_models/include/fuse_models/odometry_3d_publisher.hpp index dc623ad99..8f4853dc1 100644 --- a/fuse_models/include/fuse_models/odometry_3d_publisher.hpp +++ b/fuse_models/include/fuse_models/odometry_3d_publisher.hpp @@ -118,6 +118,10 @@ class Odometry3DPublisher : public fuse_core::AsyncPublisher * @brief Destructor */ virtual ~Odometry3DPublisher() = default; + Odometry3DPublisher(Odometry3DPublisher const&) = delete; + Odometry3DPublisher(Odometry3DPublisher&&) = delete; + Odometry3DPublisher& operator=(Odometry3DPublisher const&) = delete; + Odometry3DPublisher& operator=(Odometry3DPublisher&&) = delete; /** * @brief Shadowing extension to the AsyncPublisher::initialize call @@ -126,6 +130,12 @@ class Odometry3DPublisher : public fuse_core::AsyncPublisher const std::string& name) override; protected: + // helper function + void predict(tf2::Transform& pose, nav_msgs::msg::Odometry& odom_output, rclcpp::Time const& to_predict_to, + geometry_msgs::msg::AccelWithCovarianceStamped acceleration_output, bool latest_covariance_valid) const; + void publishTF(nav_msgs::msg::Odometry const& odom_output, tf2::Transform& pose); + + void predictTimestampCallback(builtin_interfaces::msg::Time const& time_msg); /** * @brief Perform any required post-construction initialization, such as advertising publishers or * reading from the parameter server. @@ -216,7 +226,11 @@ class Odometry3DPublisher : public fuse_core::AsyncPublisher std::unique_ptr tf_buffer_; rclcpp::Publisher::SharedPtr odom_pub_; + rclcpp::Publisher::SharedPtr odom_pub_predict_; rclcpp::Publisher::SharedPtr acceleration_pub_; + rclcpp::Subscription::SharedPtr predict_timestamp_sub_; + rclcpp::Time predict_timestamp_; + std::mutex predict_timestamp_mutex_; std::shared_ptr tf_broadcaster_ = nullptr; std::unique_ptr tf_listener_; diff --git a/fuse_models/include/fuse_models/parameters/odometry_3d_publisher_params.hpp b/fuse_models/include/fuse_models/parameters/odometry_3d_publisher_params.hpp index 21cb0a29e..e74fdcb5e 100644 --- a/fuse_models/include/fuse_models/parameters/odometry_3d_publisher_params.hpp +++ b/fuse_models/include/fuse_models/parameters/odometry_3d_publisher_params.hpp @@ -36,10 +36,8 @@ #include -#include #include #include -#include #include @@ -77,6 +75,10 @@ struct Odometry3DPublisherParams : public ParameterBase { publish_tf = fuse_core::getParam(interfaces, fuse_core::joinParameterName(ns, "publish_tf"), publish_tf); invert_tf = fuse_core::getParam(interfaces, fuse_core::joinParameterName(ns, "invert_tf"), invert_tf); + predict_to_future = + fuse_core::getParam(interfaces, fuse_core::joinParameterName(ns, "predict_to_future"), predict_to_future); + predict_timestamp_topic = fuse_core::getParam( + interfaces, fuse_core::joinParameterName(ns, "predict_timestamp_topic"), predict_timestamp_topic); predict_to_current_time = fuse_core::getParam( interfaces, fuse_core::joinParameterName(ns, "predict_to_current_time"), predict_to_current_time); predict_with_acceleration = fuse_core::getParam( @@ -158,6 +160,9 @@ struct Odometry3DPublisherParams : public ParameterBase std::string base_link_output_frame_id{ base_link_frame_id }; std::string world_frame_id{ odom_frame_id }; std::string topic{ "odometry/filtered" }; + bool predict_to_future{ false }; + std::string predict_timestamp_topic{ "predict_time" }; + std::string predict_topic{ "predicted_odometry/filtered" }; std::string acceleration_topic{ "acceleration/filtered" }; ceres::Covariance::Options covariance_options; }; diff --git a/fuse_models/src/odometry_3d_publisher.cpp b/fuse_models/src/odometry_3d_publisher.cpp index ec2649f91..202161b46 100644 --- a/fuse_models/src/odometry_3d_publisher.cpp +++ b/fuse_models/src/odometry_3d_publisher.cpp @@ -38,6 +38,8 @@ #include #include #include +#include +#include #include #include #include @@ -112,10 +114,27 @@ void Odometry3DPublisher::onInit() odom_pub_ = rclcpp::create_publisher(interfaces_, params_.topic, params_.queue_size, pub_options); + + if (params_.predict_to_future) + { + odom_pub_predict_ = rclcpp::create_publisher(interfaces_, params_.predict_topic, + params_.queue_size, pub_options); + + predict_timestamp_sub_ = rclcpp::create_subscription( + interfaces_, params_.predict_timestamp_topic, params_.queue_size, + std::bind(&Odometry3DPublisher::predictTimestampCallback, this, std::placeholders::_1)); + } + acceleration_pub_ = rclcpp::create_publisher( interfaces_, params_.acceleration_topic, params_.queue_size, pub_options); } +void Odometry3DPublisher::predictTimestampCallback(builtin_interfaces::msg::Time const& time_msg) +{ + std::lock_guard const lock(predict_timestamp_mutex_); + predict_timestamp_ = rclcpp::Time(time_msg); +} + void Odometry3DPublisher::notifyCallback(fuse_core::Transaction::ConstSharedPtr transaction, fuse_core::Graph::ConstSharedPtr graph) { @@ -124,7 +143,7 @@ void Odometry3DPublisher::notifyCallback(fuse_core::Transaction::ConstSharedPtr if (0u == latest_stamp.nanoseconds()) { { - std::lock_guard lock(mutex_); + std::lock_guard const lock(mutex_); latest_stamp_ = latest_stamp; } @@ -146,7 +165,7 @@ void Odometry3DPublisher::notifyCallback(fuse_core::Transaction::ConstSharedPtr if (!getState(*graph, latest_stamp, device_id_, position_uuid, orientation_uuid, velocity_linear_uuid, velocity_angular_uuid, acceleration_linear_uuid, odom_output, acceleration_output)) { - std::lock_guard lock(mutex_); + std::lock_guard const lock(mutex_); latest_stamp_ = latest_stamp; return; } @@ -324,7 +343,7 @@ void Odometry3DPublisher::notifyCallback(fuse_core::Transaction::ConstSharedPtr } { - std::lock_guard lock(mutex_); + std::lock_guard const lock(mutex_); latest_stamp_ = latest_stamp; latest_covariance_stamp_ = latest_covariance_stamp; @@ -345,7 +364,7 @@ void Odometry3DPublisher::onStart() // TODO(CH3): Add this to a separate callback group for async behavior publish_timer_ = rclcpp::create_timer(interfaces_, clock_, std::chrono::duration(1.0 / params_.publish_frequency), - std::move(std::bind(&Odometry3DPublisher::publishTimerCallback, this)), cb_group_); + std::bind(&Odometry3DPublisher::publishTimerCallback, this), cb_group_); delayed_throttle_filter_.reset(); } @@ -420,23 +439,157 @@ bool Odometry3DPublisher::getState(const fuse_core::Graph& graph, const rclcpp:: return true; } +void Odometry3DPublisher::predict(tf2::Transform& pose, nav_msgs::msg::Odometry& odom_output, + rclcpp::Time const& to_predict_to, + geometry_msgs::msg::AccelWithCovarianceStamped acceleration_output, + bool latest_covariance_valid) const +{ + const double dt = to_predict_to.seconds() - rclcpp::Time(odom_output.header.stamp).seconds(); + // Convert pose in Eigen representation + fuse_core::Vector3d position; + fuse_core::Vector3d velocity_linear; + fuse_core::Vector3d velocity_angular; + Eigen::Quaterniond orientation; + position << pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z(); + orientation.x() = pose.getRotation().x(); + orientation.y() = pose.getRotation().y(); + orientation.z() = pose.getRotation().z(); + orientation.w() = pose.getRotation().w(); + velocity_linear << odom_output.twist.twist.linear.x, odom_output.twist.twist.linear.y, + odom_output.twist.twist.linear.z; + velocity_angular << odom_output.twist.twist.angular.x, odom_output.twist.twist.angular.y, + odom_output.twist.twist.angular.z; + + fuse_core::Matrix15d jacobian; + + fuse_core::Vector3d acceleration_linear; + if (params_.predict_with_acceleration) + { + acceleration_linear << acceleration_output.accel.accel.linear.x, acceleration_output.accel.accel.linear.y, + acceleration_output.accel.accel.linear.z; + } + + ::fuse_models::predict(position, orientation, velocity_linear, velocity_angular, acceleration_linear, dt, position, + orientation, velocity_linear, velocity_angular, acceleration_linear, jacobian); + + // Convert back to tf2 representation + pose.setOrigin(tf2::Vector3(position.x(), position.y(), position.z())); + pose.setRotation(tf2::Quaternion(orientation.x(), orientation.y(), orientation.z(), orientation.w())); + + odom_output.pose.pose.position.x = position.x(); + odom_output.pose.pose.position.y = position.y(); + odom_output.pose.pose.position.z = position.z(); + odom_output.pose.pose.orientation.x = orientation.x(); + odom_output.pose.pose.orientation.y = orientation.y(); + odom_output.pose.pose.orientation.z = orientation.z(); + odom_output.pose.pose.orientation.w = orientation.w(); + + odom_output.twist.twist.linear.x = velocity_linear.x(); + odom_output.twist.twist.linear.y = velocity_linear.y(); + odom_output.twist.twist.linear.z = velocity_linear.z(); + odom_output.twist.twist.angular.x = velocity_angular.x(); + odom_output.twist.twist.angular.y = velocity_angular.y(); + odom_output.twist.twist.angular.z = velocity_angular.z(); + + if (params_.predict_with_acceleration) + { + acceleration_output.accel.accel.linear.x = acceleration_linear.x(); + acceleration_output.accel.accel.linear.y = acceleration_linear.y(); + acceleration_output.accel.accel.linear.z = acceleration_linear.z(); + } + + odom_output.header.stamp = to_predict_to; + acceleration_output.header.stamp = to_predict_to; + + // Either the last covariance computation was skipped because there was no subscriber, + // or it failed + if (latest_covariance_valid) + { + fuse_core::Matrix15d covariance; + covariance.setZero(); + Eigen::Map pose_covariance(odom_output.pose.covariance.data()); + Eigen::Map twist_covariance(odom_output.twist.covariance.data()); + Eigen::Map acceleration_covariance(acceleration_output.accel.covariance.data()); + + covariance.block<6, 6>(0, 0) = pose_covariance; + covariance.block<6, 6>(6, 6) = twist_covariance; + covariance.block<3, 3>(12, 12) = acceleration_covariance; + + covariance = jacobian * covariance * jacobian.transpose(); + + auto process_noise_covariance = params_.process_noise_covariance; + if (params_.scale_process_noise) + { + common::scaleProcessNoiseCovariance(process_noise_covariance, velocity_linear, velocity_angular, + params_.velocity_linear_norm_min_, params_.velocity_angular_norm_min_); + } + + covariance.noalias() += dt * process_noise_covariance; + + pose_covariance = covariance.block<6, 6>(0, 0); + twist_covariance = covariance.block<6, 6>(6, 6); + acceleration_covariance = covariance.block<3, 3>(12, 12); + } +} + +void Odometry3DPublisher::publishTF(nav_msgs::msg::Odometry const& odom_output, tf2::Transform& pose) +{ + auto frame_id = odom_output.header.frame_id; + auto child_frame_id = odom_output.child_frame_id; + + if (params_.invert_tf) + { + pose = pose.inverse(); + std::swap(frame_id, child_frame_id); + } + + geometry_msgs::msg::TransformStamped trans; + trans.header.stamp = odom_output.header.stamp; + trans.header.frame_id = frame_id; + trans.child_frame_id = child_frame_id; + trans.transform = tf2::toMsg(pose); + if (!params_.invert_tf && params_.world_frame_id == params_.map_frame_id) + { + try + { + auto base_to_odom = tf_buffer_->lookupTransform(params_.base_link_frame_id, params_.odom_frame_id, + trans.header.stamp, params_.tf_timeout); + + geometry_msgs::msg::TransformStamped map_to_odom; + tf2::doTransform(base_to_odom, map_to_odom, trans); + map_to_odom.child_frame_id = params_.odom_frame_id; + trans = map_to_odom; + } + catch (const std::exception& e) + { + RCLCPP_WARN_STREAM_THROTTLE(logger_, *clock_, 5.0 * 1000, + "Could not lookup the " << params_.base_link_frame_id << "->" << params_.odom_frame_id + << " transform. Error: " << e.what()); + + return; + } + } + + tf_broadcaster_->sendTransform(trans); +} + void Odometry3DPublisher::publishTimerCallback() { rclcpp::Time latest_stamp; - rclcpp::Time latest_covariance_stamp; - bool latest_covariance_valid; + bool latest_covariance_valid = false; nav_msgs::msg::Odometry odom_output; geometry_msgs::msg::AccelWithCovarianceStamped acceleration_output; { - std::lock_guard lock(mutex_); + std::lock_guard const lock(mutex_); latest_stamp = latest_stamp_; - latest_covariance_stamp = latest_covariance_stamp_; latest_covariance_valid = latest_covariance_valid_; odom_output = odom_output_; acceleration_output = acceleration_output_; } + nav_msgs::msg::Odometry odom_output_predict = odom_output; + if (0u == latest_stamp.nanoseconds()) { RCLCPP_WARN_STREAM_EXPRESSION(logger_, delayed_throttle_filter_.isEnabled(), @@ -447,141 +600,32 @@ void Odometry3DPublisher::publishTimerCallback() tf2::Transform pose; tf2::fromMsg(odom_output.pose.pose, pose); + tf2::Transform pose_predict; + tf2::fromMsg(odom_output_predict.pose.pose, pose_predict); + // If requested, we need to project our state forward in time using the 3D kinematic model if (params_.predict_to_current_time) { - rclcpp::Time timer_now = interfaces_.get_node_clock_interface()->get_clock()->now(); - - // Convert pose in Eigen representation - fuse_core::Vector3d position, velocity_linear, velocity_angular; - Eigen::Quaterniond orientation; - position << pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z(); - orientation.x() = pose.getRotation().x(); - orientation.y() = pose.getRotation().y(); - orientation.z() = pose.getRotation().z(); - orientation.w() = pose.getRotation().w(); - velocity_linear << odom_output.twist.twist.linear.x, odom_output.twist.twist.linear.y, - odom_output.twist.twist.linear.z; - velocity_angular << odom_output.twist.twist.angular.x, odom_output.twist.twist.angular.y, - odom_output.twist.twist.angular.z; - - const double dt = timer_now.seconds() - rclcpp::Time(odom_output.header.stamp).seconds(); - - fuse_core::Matrix15d jacobian; - - fuse_core::Vector3d acceleration_linear; - if (params_.predict_with_acceleration) - { - acceleration_linear << acceleration_output.accel.accel.linear.x, acceleration_output.accel.accel.linear.y, - acceleration_output.accel.accel.linear.z; - } - - predict(position, orientation, velocity_linear, velocity_angular, acceleration_linear, dt, position, orientation, - velocity_linear, velocity_angular, acceleration_linear, jacobian); - - // Convert back to tf2 representation - pose.setOrigin(tf2::Vector3(position.x(), position.y(), position.z())); - pose.setRotation(tf2::Quaternion(orientation.x(), orientation.y(), orientation.z(), orientation.w())); - - odom_output.pose.pose.position.x = position.x(); - odom_output.pose.pose.position.y = position.y(); - odom_output.pose.pose.position.z = position.z(); - odom_output.pose.pose.orientation.x = orientation.x(); - odom_output.pose.pose.orientation.y = orientation.y(); - odom_output.pose.pose.orientation.z = orientation.z(); - odom_output.pose.pose.orientation.w = orientation.w(); - - odom_output.twist.twist.linear.x = velocity_linear.x(); - odom_output.twist.twist.linear.y = velocity_linear.y(); - odom_output.twist.twist.linear.z = velocity_linear.z(); - odom_output.twist.twist.angular.x = velocity_angular.x(); - odom_output.twist.twist.angular.y = velocity_angular.y(); - odom_output.twist.twist.angular.z = velocity_angular.z(); - - if (params_.predict_with_acceleration) - { - acceleration_output.accel.accel.linear.x = acceleration_linear.x(); - acceleration_output.accel.accel.linear.y = acceleration_linear.y(); - acceleration_output.accel.accel.linear.z = acceleration_linear.z(); - } - - odom_output.header.stamp = timer_now; - acceleration_output.header.stamp = timer_now; - - // Either the last covariance computation was skipped because there was no subscriber, - // or it failed - if (latest_covariance_valid) - { - fuse_core::Matrix15d covariance; - covariance.setZero(); - Eigen::Map pose_covariance(odom_output.pose.covariance.data()); - Eigen::Map twist_covariance(odom_output.twist.covariance.data()); - Eigen::Map acceleration_covariance(acceleration_output.accel.covariance.data()); - - covariance.block<6, 6>(0, 0) = pose_covariance; - covariance.block<6, 6>(6, 6) = twist_covariance; - covariance.block<3, 3>(12, 12) = acceleration_covariance; - - covariance = jacobian * covariance * jacobian.transpose(); - - auto process_noise_covariance = params_.process_noise_covariance; - if (params_.scale_process_noise) - { - common::scaleProcessNoiseCovariance(process_noise_covariance, velocity_linear, velocity_angular, - params_.velocity_linear_norm_min_, params_.velocity_angular_norm_min_); - } - - covariance.noalias() += dt * process_noise_covariance; - - pose_covariance = covariance.block<6, 6>(0, 0); - twist_covariance = covariance.block<6, 6>(6, 6); - acceleration_covariance = covariance.block<3, 3>(12, 12); - } + rclcpp::Time const timer_now = interfaces_.get_node_clock_interface()->get_clock()->now(); + predict(pose, odom_output, timer_now, acceleration_output, latest_covariance_valid); } odom_pub_->publish(odom_output); acceleration_pub_->publish(acceleration_output); - - if (params_.publish_tf) + if (params_.predict_to_future) { - auto frame_id = odom_output.header.frame_id; - auto child_frame_id = odom_output.child_frame_id; - - if (params_.invert_tf) + rclcpp::Time predict_time; { - pose = pose.inverse(); - std::swap(frame_id, child_frame_id); - } - - geometry_msgs::msg::TransformStamped trans; - trans.header.stamp = odom_output.header.stamp; - trans.header.frame_id = frame_id; - trans.child_frame_id = child_frame_id; - trans.transform = tf2::toMsg(pose); - if (!params_.invert_tf && params_.world_frame_id == params_.map_frame_id) - { - try - { - auto base_to_odom = tf_buffer_->lookupTransform(params_.base_link_frame_id, params_.odom_frame_id, - trans.header.stamp, params_.tf_timeout); - - geometry_msgs::msg::TransformStamped map_to_odom; - tf2::doTransform(base_to_odom, map_to_odom, trans); - map_to_odom.child_frame_id = params_.odom_frame_id; - trans = map_to_odom; - } - catch (const std::exception& e) - { - RCLCPP_WARN_STREAM_THROTTLE(logger_, *clock_, 5.0 * 1000, - "Could not lookup the " << params_.base_link_frame_id << "->" - << params_.odom_frame_id - << " transform. Error: " << e.what()); - - return; - } + std::lock_guard const lock(predict_timestamp_mutex_); + predict_time = predict_timestamp_; } + predict(pose_predict, odom_output_predict, predict_time, acceleration_output, latest_covariance_valid); + odom_pub_predict_->publish(odom_output_predict); + } - tf_broadcaster_->sendTransform(trans); + if (params_.publish_tf) + { + publishTF(odom_output, pose); } } diff --git a/fuse_optimizers/include/fuse_optimizers/batch_optimizer.hpp b/fuse_optimizers/include/fuse_optimizers/batch_optimizer.hpp index d3d905322..969df9624 100644 --- a/fuse_optimizers/include/fuse_optimizers/batch_optimizer.hpp +++ b/fuse_optimizers/include/fuse_optimizers/batch_optimizer.hpp @@ -39,11 +39,9 @@ #include #include #include -#include #include #include #include -#include #include #include @@ -111,13 +109,17 @@ class BatchOptimizer : public Optimizer * @param[in] interfaces The node interfaces for the node driving the optimizer * @param[in] graph The graph used with the optimizer */ - BatchOptimizer(fuse_core::node_interfaces::NodeInterfaces interfaces, - fuse_core::Graph::UniquePtr graph = nullptr); + explicit BatchOptimizer(fuse_core::node_interfaces::NodeInterfaces interfaces, + fuse_core::Graph::UniquePtr graph = nullptr); /** * @brief Destructor */ virtual ~BatchOptimizer(); + BatchOptimizer(BatchOptimizer const&) = delete; + BatchOptimizer(BatchOptimizer&&) = delete; + BatchOptimizer& operator=(BatchOptimizer const&) = delete; + BatchOptimizer& operator=(BatchOptimizer&&) = delete; protected: /** diff --git a/fuse_optimizers/include/fuse_optimizers/batch_optimizer_params.hpp b/fuse_optimizers/include/fuse_optimizers/batch_optimizer_params.hpp index 5d64d5f9f..4977c92d8 100644 --- a/fuse_optimizers/include/fuse_optimizers/batch_optimizer_params.hpp +++ b/fuse_optimizers/include/fuse_optimizers/batch_optimizer_params.hpp @@ -37,9 +37,7 @@ #include -#include #include -#include #include #include diff --git a/fuse_optimizers/include/fuse_optimizers/variable_stamp_index.hpp b/fuse_optimizers/include/fuse_optimizers/variable_stamp_index.hpp index ab166db75..425ab73a2 100644 --- a/fuse_optimizers/include/fuse_optimizers/variable_stamp_index.hpp +++ b/fuse_optimizers/include/fuse_optimizers/variable_stamp_index.hpp @@ -69,6 +69,10 @@ class VariableStampIndex * @brief Destructor */ virtual ~VariableStampIndex() = default; + VariableStampIndex(VariableStampIndex const&) = default; + VariableStampIndex(VariableStampIndex&&) = default; + VariableStampIndex& operator=(VariableStampIndex const&) = default; + VariableStampIndex& operator=(VariableStampIndex&&) = default; /** * @brief Return true if no variables exist in the index diff --git a/fuse_optimizers/src/batch_optimizer.cpp b/fuse_optimizers/src/batch_optimizer.cpp index c87fa4b28..78b530e99 100644 --- a/fuse_optimizers/src/batch_optimizer.cpp +++ b/fuse_optimizers/src/batch_optimizer.cpp @@ -32,7 +32,6 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include #include #include #include @@ -79,7 +78,7 @@ BatchOptimizer::~BatchOptimizer() void BatchOptimizer::applyMotionModelsToQueue() { // We need get the pending transactions from the queue - std::lock_guard pending_transactions_lock(pending_transactions_mutex_); + std::lock_guard const pending_transactions_lock(pending_transactions_mutex_); rclcpp::Time current_time; // Use the most recent transaction time as the current time if (!pending_transactions_.empty()) @@ -108,16 +107,14 @@ void BatchOptimizer::applyMotionModelsToQueue() pending_transactions_.erase(pending_transactions_.begin()); continue; } - else - { - // Stop processing future transactions. Try again next time. - break; - } + + // Stop processing future transactions. Try again next time. + break; } // Merge the sensor+motion model transactions into a combined transaction that will be applied // directly to the graph { - std::lock_guard combined_transaction_lock(combined_transaction_mutex_); + std::lock_guard const combined_transaction_lock(combined_transaction_mutex_); combined_transaction_->merge(*element.transaction, true); } // We are done with this transaction. Delete it from the queue. @@ -147,7 +144,7 @@ void BatchOptimizer::optimizationLoop() // Copy the combined transaction so it can be shared with all the plugins fuse_core::Transaction::ConstSharedPtr const_transaction; { - std::lock_guard lock(combined_transaction_mutex_); + std::lock_guard const lock(combined_transaction_mutex_); const_transaction = std::move(combined_transaction_); combined_transaction_ = fuse_core::Transaction::make_shared(); } @@ -156,7 +153,7 @@ void BatchOptimizer::optimizationLoop() // Optimize the entire graph graph_->optimize(params_.solver_options); // Make a copy of the graph to share - fuse_core::Graph::ConstSharedPtr const_graph = graph_->clone(); + fuse_core::Graph::ConstSharedPtr const const_graph = graph_->clone(); // Optimization is complete. Notify all the things about the graph changes. notify(const_transaction, const_graph); // Clear the request flag now that this optimization cycle is complete @@ -175,7 +172,7 @@ void BatchOptimizer::optimizerTimerCallback() applyMotionModelsToQueue(); // Check if there is any pending information to be applied to the graph. { - std::lock_guard lock(combined_transaction_mutex_); + std::lock_guard const lock(combined_transaction_mutex_); optimization_request_ = !combined_transaction_->empty(); } // If there is some pending work, trigger the next optimization cycle. @@ -194,11 +191,11 @@ void BatchOptimizer::transactionCallback(const std::string& sensor_name, fuse_co // Or we have "started" already, and the new transaction is after the starting time. auto transaction_clock_type = transaction->stamp().get_clock_type(); - rclcpp::Time transaction_time = transaction->stamp(); + rclcpp::Time const transaction_time = transaction->stamp(); rclcpp::Time last_pending_time(0, 0, transaction_clock_type); // NOTE(CH3): Uninitialized if (!started_ || transaction_time >= start_time_) { - std::lock_guard lock(pending_transactions_mutex_); + std::lock_guard const lock(pending_transactions_mutex_); pending_transactions_.emplace(transaction_time, TransactionQueueElement(sensor_name, std::move(transaction))); last_pending_time = pending_transactions_.rbegin()->first; } @@ -222,7 +219,7 @@ void BatchOptimizer::transactionCallback(const std::string& sensor_name, fuse_co { purge_time = last_pending_time - params_.transaction_timeout; } - std::lock_guard lock(pending_transactions_mutex_); + std::lock_guard const lock(pending_transactions_mutex_); auto purge_iter = pending_transactions_.lower_bound(purge_time); pending_transactions_.erase(pending_transactions_.begin(), purge_iter); } @@ -241,7 +238,7 @@ void BatchOptimizer::setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& status.add("Started", started_); { - std::lock_guard lock(pending_transactions_mutex_); + std::lock_guard const lock(pending_transactions_mutex_); status.add("Pending Transactions", pending_transactions_.size()); } } diff --git a/fuse_optimizers/src/variable_stamp_index.cpp b/fuse_optimizers/src/variable_stamp_index.cpp index a2fbd3a04..032ae1de4 100644 --- a/fuse_optimizers/src/variable_stamp_index.cpp +++ b/fuse_optimizers/src/variable_stamp_index.cpp @@ -33,7 +33,6 @@ */ #include -#include #include #include @@ -54,10 +53,7 @@ rclcpp::Time VariableStampIndex::currentStamp() const { return iter->second; } - else - { - return rclcpp::Time(0, 0, RCL_ROS_TIME); - } + return { 0, 0, RCL_ROS_TIME }; } void VariableStampIndex::addNewTransaction(const fuse_core::Transaction& transaction) @@ -94,8 +90,8 @@ void VariableStampIndex::applyAddedVariables(const fuse_core::Transaction& trans { for (const auto& variable : transaction.addedVariables()) { - auto stamped_variable = dynamic_cast(&variable); - if (stamped_variable) + const auto* stamped_variable = dynamic_cast(&variable); + if (stamped_variable != nullptr) { stamped_index_[variable.uuid()] = stamped_variable->stamp(); } @@ -107,7 +103,7 @@ void VariableStampIndex::applyRemovedConstraints(const fuse_core::Transaction& t { for (const auto& constraint_uuid : transaction.removedConstraints()) { - for (auto& variable_uuid : constraints_[constraint_uuid]) + for (const auto& variable_uuid : constraints_[constraint_uuid]) { variables_[variable_uuid].erase(constraint_uuid); } diff --git a/fuse_tutorials/config/fuse_apriltag_tutorial.rviz b/fuse_tutorials/config/fuse_apriltag_tutorial.rviz new file mode 100644 index 000000000..832ca6afc --- /dev/null +++ b/fuse_tutorials/config/fuse_apriltag_tutorial.rviz @@ -0,0 +1,253 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Odometry1/Shape1 + - /Odometry2/Shape1 + - /Odometry3 + Splitter Ratio: 0.5 + Tree Height: 555 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: false + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 0; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /ground_truth + Value: true + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 0; 255; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /odom_filtered + Value: true + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: false + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /predicted_odometry/filtered + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 10.72309398651123 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002b4000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000025300fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 60 + Y: 60 diff --git a/fuse_tutorials/config/fuse_apriltag_tutorial.yaml b/fuse_tutorials/config/fuse_apriltag_tutorial.yaml index 51531cbe9..5e1605030 100644 --- a/fuse_tutorials/config/fuse_apriltag_tutorial.yaml +++ b/fuse_tutorials/config/fuse_apriltag_tutorial.yaml @@ -14,7 +14,7 @@ state_estimator: 3d_motion_model: # x, y, z, roll, pitch, yaw, x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel, x_acc, y_acc, z_acc # use high values for the acceleration process noise because we aren't measuring the applied forces - process_noise_diagonal: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10., 10., 10.] + process_noise_diagonal: [0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 0.000001, 10., 10., 10.] sensor_models: initial_localization_sensor: @@ -53,3 +53,4 @@ state_estimator: world_frame_id: 'odom' publish_tf: true publish_frequency: 100.0 + predict_to_future: true diff --git a/fuse_tutorials/launch/fuse_3d_tutorial.launch.py b/fuse_tutorials/launch/fuse_3d_tutorial.launch.py index f57d66dc1..664d83e50 100755 --- a/fuse_tutorials/launch/fuse_3d_tutorial.launch.py +++ b/fuse_tutorials/launch/fuse_3d_tutorial.launch.py @@ -15,9 +15,8 @@ # limitations under the License. from launch import LaunchDescription -from launch.actions import ExecuteProcess from launch.substitutions import PathJoinSubstitution -from launch_ros.actions import Node, SetParameter +from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare diff --git a/fuse_tutorials/launch/fuse_apriltag_tutorial.launch.py b/fuse_tutorials/launch/fuse_apriltag_tutorial.launch.py index 6df7100cd..62e4042a5 100644 --- a/fuse_tutorials/launch/fuse_apriltag_tutorial.launch.py +++ b/fuse_tutorials/launch/fuse_apriltag_tutorial.launch.py @@ -59,7 +59,7 @@ def generate_launch_description(): "-d", [ PathJoinSubstitution( - [pkg_dir, "config", "fuse_3d_tutorial.rviz"] + [pkg_dir, "config", "fuse_apriltag_tutorial.rviz"] ) ], ], diff --git a/fuse_tutorials/src/apriltag_simulator.cpp b/fuse_tutorials/src/apriltag_simulator.cpp index c1bce41d1..43e952834 100644 --- a/fuse_tutorials/src/apriltag_simulator.cpp +++ b/fuse_tutorials/src/apriltag_simulator.cpp @@ -62,6 +62,7 @@ constexpr double aprilTagOrientationSigma = 0.25; //!< the april tag orientatio constexpr size_t numAprilTags = 8; //!< the number of april tags constexpr double detectionProbability = 0.5; //!< the probability that any given april tag is detectable on a given tick of the simulation +constexpr double futurePredictionTimeSeconds = 0.1; } // namespace /** @@ -314,6 +315,7 @@ int main(int argc, char** argv) // create the ground truth publisher auto ground_truth_publisher = node->create_publisher("ground_truth", 1); + auto predict_time_publisher = node->create_publisher("predict_time", 1); // Initialize the robot state (state variables are zero-initialized) auto state = Robot(); @@ -336,6 +338,11 @@ int main(int argc, char** argv) // store the first time this runs (since it won't start running exactly at a multiple of `motion_duration`) static auto const firstTime = node->now(); auto const now = node->now(); + builtin_interfaces::msg::Time predict_time(now); + + // predict into the future + predict_time.nanosec += static_cast(futurePredictionTimeSeconds * 1e9); + predict_time_publisher->publish(predict_time); // compensate for the original time offset double const now_d = (now - firstTime).seconds();