-
Notifications
You must be signed in to change notification settings - Fork 123
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
Vision constraints #352
Draft
oscarmendezm
wants to merge
12
commits into
devel
Choose a base branch
from
vision_constraints
base: devel
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Draft
Vision constraints #352
Changes from all commits
Commits
Show all changes
12 commits
Select commit
Hold shift + click to select a range
5b22af0
Adding python scripts to generate test cases.
oscarmendezm 3a2a561
Minor PR Fixes.
oscarmendezm dcc0ff1
Improved vision constraints. Includes Snavelly,
oscarmendezm 5e9737e
Adding simple covariance version which uses
oscarmendezm a5e3c8c
Linting fixes for CI.
oscarmendezm a55be22
Applying simple covariance correctly,
oscarmendezm bd3119a
Small fixes for linting and testing.
oscarmendezm f216d41
More linting for CI errors.
oscarmendezm 822ab4a
Fixing base_camera.h spacing.
oscarmendezm 3188b48
PR Review.
oscarmendezm e17b717
Changing fixed3d_landmark to use a variable number of residuals.
oscarmendezm 119ccf6
Fixing bug with number of residual calculation.
oscarmendezm 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
There are no files selected for viewing
This file contains 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
This file contains 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
This file contains 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
229 changes: 229 additions & 0 deletions
229
fuse_constraints/include/fuse_constraints/fixed_3d_landmark_simple_covariance_constraint.h
This file contains 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,229 @@ | ||
/* | ||
* Software License Agreement (BSD License) | ||
* | ||
* Author: Oscar Mendez | ||
* Created on Mon Nov 12 2023 | ||
* | ||
* Copyright (c) 2023, Locus Robotics | ||
* All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions | ||
* are met: | ||
* | ||
* * Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* * Redistributions in binary form must reproduce the above | ||
* copyright notice, this list of conditions and the following | ||
* disclaimer in the documentation and/or other materials provided | ||
* with the distribution. | ||
* * Neither the name of the copyright holder nor the names of its | ||
* contributors may be used to endorse or promote products derived | ||
* from this software without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS | ||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE | ||
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, | ||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, | ||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; | ||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER | ||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT | ||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
*/ | ||
#ifndef FUSE_CONSTRAINTS_FIXED_3D_LANDMARK_SIMPLE_COVARIANCE_CONSTRAINT_H | ||
#define FUSE_CONSTRAINTS_FIXED_3D_LANDMARK_SIMPLE_COVARIANCE_CONSTRAINT_H | ||
|
||
#include <fuse_core/constraint.h> | ||
#include <fuse_core/eigen.h> | ||
#include <fuse_core/fuse_macros.h> | ||
#include <fuse_core/serialization.h> | ||
#include <fuse_core/uuid.h> | ||
#include <fuse_variables/orientation_3d_stamped.h> | ||
#include <fuse_variables/position_3d_stamped.h> | ||
#include <fuse_variables/pinhole_camera.h> | ||
|
||
#include <boost/serialization/access.hpp> | ||
#include <boost/serialization/base_object.hpp> | ||
#include <boost/serialization/export.hpp> | ||
#include <Eigen/Dense> | ||
|
||
#include <ostream> | ||
#include <string> | ||
#include <vector> | ||
|
||
namespace fuse_constraints | ||
{ | ||
|
||
/** | ||
* @brief A constraint that represents an observation of a 3D landmark (ARTag or Similar) | ||
* | ||
* A landmark is represented as a 3D pose (3D position and a 3D orientation). This class takes | ||
* the ground truth location of the 3D landmark and applies a reprojection-error based constraint | ||
* on the position, orientation and calibration of the camera that observed the landmark. | ||
* | ||
* In most cases, the camera calibration should be held fixed as a single landmark does not present enough | ||
* points to accurately constrain the pose AND the calibraton. | ||
* | ||
*/ | ||
class Fixed3DLandmarkSimpleCovarianceConstraint : public fuse_core::Constraint | ||
{ | ||
public: | ||
FUSE_CONSTRAINT_DEFINITIONS_WITH_EIGEN(Fixed3DLandmarkSimpleCovarianceConstraint); | ||
|
||
/** | ||
* @brief Default constructor | ||
*/ | ||
Fixed3DLandmarkSimpleCovarianceConstraint() = default; | ||
|
||
/** | ||
* @brief Create a constraint using a known 3D fiducial marker | ||
* | ||
* @param[in] source The name of the sensor or motion model that generated this constraint | ||
* @param[in] position The variable representing the position components of the landmark pose | ||
* @param[in] orientation The variable representing the orientation components of the marker pose | ||
* @param[in] calibraton The intrinsic calibration parameters of the camera (4x1 vector: cx, cy, fx, fy). | ||
* NOTE: Best practice is to fix this variable unless we have several observations | ||
* with the same camera | ||
* @param[in] pts3d Matrix of 3D points in marker coordiate frame. | ||
* @param[in] observations The 2D (pixel) observations of each marker's corners. | ||
* @param[in] mean The measured/prior pose of the marker as a vector (7x1 vector: x, y, z, qw, qx, qy, qz) | ||
* @param[in] covariance The detection covariance, in pixels (2x2 matrix: u, v) | ||
*/ | ||
Fixed3DLandmarkSimpleCovarianceConstraint(const std::string& source, | ||
const fuse_variables::Position3DStamped& position, | ||
const fuse_variables::Orientation3DStamped& orientation, | ||
const fuse_variables::PinholeCamera& calibraton, | ||
const fuse_core::MatrixXd& pts3d, const fuse_core::MatrixXd& observations, | ||
const fuse_core::Vector7d& mean, const fuse_core::Matrix2d& covariance); | ||
|
||
/** | ||
* @brief Create a constraint using a known 3D fiducial marker. Convenience constructor for the special case of | ||
* an ARTag with 4 corners. | ||
* | ||
* @param[in] source The name of the sensor or motion model that generated this constraint | ||
* @param[in] position The variable representing the position components of the marker pose | ||
* @param[in] orientation The variable representing the orientation components of the marker pose | ||
* @param[in] calibraton The intrinsic calibration parameters of the camera (4x1 vector: cx, cy, fx, fy). | ||
* NOTE: Best practice is to fix this variable unless we have several observations | ||
* with the same camera | ||
* @param[in] marker_size The size of the marker, in meters. Assumed to be square. | ||
* @param[in] observations The 2D (pixel) observations of each marker's corners. | ||
* @param[in] mean The measured/prior pose of the marker as a vector (7x1 vector: x, y, z, qw, qx, qy, qz) | ||
* @param[in] covariance The detection covariance, in pixels (2x2 matrix: u, v) | ||
*/ | ||
Fixed3DLandmarkSimpleCovarianceConstraint(const std::string& source, | ||
const fuse_variables::Position3DStamped& position, | ||
const fuse_variables::Orientation3DStamped& orientation, | ||
const fuse_variables::PinholeCamera& calibraton, const double& marker_size, | ||
const fuse_core::MatrixXd& observations, const fuse_core::Vector7d& mean, | ||
const fuse_core::Matrix2d& covariance); | ||
|
||
/** | ||
* @brief Destructor | ||
*/ | ||
virtual ~Fixed3DLandmarkSimpleCovarianceConstraint() = default; | ||
|
||
/** | ||
* @brief Read-only access to the measured/prior vector of mean values. | ||
* | ||
* Order is (x, y, z, qw, qx, qy, qz) | ||
*/ | ||
const fuse_core::Vector7d& mean() const | ||
{ | ||
return mean_; | ||
} | ||
|
||
/** | ||
* @brief Read-only access to the square root information matrix. | ||
* | ||
* Order is (u, v) | ||
*/ | ||
const fuse_core::Matrix2d& sqrtInformation() const | ||
{ | ||
return sqrt_information_; | ||
} | ||
|
||
/** | ||
* @brief Compute the measurement covariance matrix. | ||
* | ||
* Order is (u, v) | ||
*/ | ||
fuse_core::Matrix2d covariance() const | ||
{ | ||
return (sqrt_information_.transpose() * sqrt_information_).inverse(); | ||
} | ||
|
||
/** | ||
* @brief Read-only access to the observation Matrix (Nx2). | ||
* | ||
* Order is (x, y, z) | ||
*/ | ||
const fuse_core::MatrixXd& pts3d() const | ||
{ | ||
return pts3d_; | ||
} | ||
|
||
/** | ||
* @brief Read-only access to the observation Matrix (Nx2). | ||
* | ||
* Order is (u, v) | ||
*/ | ||
const fuse_core::MatrixXd& observations() const | ||
{ | ||
return observations_; | ||
} | ||
|
||
/** | ||
* @brief Print a human-readable description of the constraint to the provided stream. | ||
* | ||
* @param[out] stream The stream to write to. Defaults to stdout. | ||
*/ | ||
void print(std::ostream& stream = std::cout) const override; | ||
|
||
/** | ||
* @brief Construct an instance of this constraint's cost function | ||
* | ||
* The function caller will own the new cost function instance. It is the responsibility of the caller to delete | ||
* the cost function object when it is no longer needed. If the pointer is provided to a Ceres::Problem object, the | ||
* Ceres::Problem object will takes ownership of the pointer and delete it during destruction. | ||
* | ||
* @return A base pointer to an instance of a derived CostFunction. | ||
*/ | ||
ceres::CostFunction* costFunction() const override; | ||
|
||
protected: | ||
fuse_core::MatrixXd pts3d_; //!< The 3D points in marker Coordinate frame | ||
fuse_core::MatrixXd observations_; //!< The 2D observations (in pixel space) of the marker at postion mean_ | ||
fuse_core::Vector7d mean_; //!< The measured/prior mean vector for this variable | ||
fuse_core::Matrix2d sqrt_information_; //!< The square root information matrix | ||
|
||
private: | ||
// Allow Boost Serialization access to private methods | ||
friend class boost::serialization::access; | ||
|
||
/** | ||
* @brief The Boost Serialize method that serializes all of the data members in to/out of the archive | ||
* | ||
* @param[in/out] archive - The archive object that holds the serialized class members | ||
* @param[in] version - The version of the archive being read/written. Generally unused. | ||
*/ | ||
template <class Archive> | ||
void serialize(Archive& archive, const unsigned int /* version */) | ||
{ | ||
archive& boost::serialization::base_object<fuse_core::Constraint>(*this); | ||
archive& pts3d_; | ||
archive& observations_; | ||
archive& mean_; | ||
archive& sqrt_information_; | ||
} | ||
}; | ||
|
||
} // namespace fuse_constraints | ||
|
||
BOOST_CLASS_EXPORT_KEY(fuse_constraints::Fixed3DLandmarkSimpleCovarianceConstraint); | ||
|
||
#endif // FUSE_CONSTRAINTS_FIXED_3D_LANDMARK_SIMPLE_COVARIANCE_CONSTRAINT_H |
Oops, something went wrong.
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.
I'm just matching the equations here to the comments posted above. Elements [2, 5] and [2, 6] have a different sign in the code versus the comments. Not sure which one is correct.
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.
Comment was wrong. Verified against paper.