![]() |
NASA Astrobee Robot Software
Astrobee Version:
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <inverse_depth_measurement.h>
Public Types | |
enum | { dimension = 1 } |
Public Member Functions | |
InverseDepthMeasurement (const double inverse_depth, const Eigen::Vector2d &image_coordinates, const Eigen::Matrix3d &intrinsics, const gtsam::Pose3 &body_T_sensor) | |
Eigen::Vector3d | Backproject (boost::optional< gtsam::Matrix & > d_backprojected_point_d_depth=boost::none) const |
boost::optional< Eigen::Vector2d > | Project (const gtsam::Pose3 &world_T_source_body, const gtsam::Pose3 &world_T_target_body, boost::optional< gtsam::Matrix & > d_projected_point_d_world_T_source_body=boost::none, boost::optional< gtsam::Matrix & > d_projected_point_d_world_T_target_body=boost::none, boost::optional< gtsam::Matrix & > d_projected_point_d_inverse_depth=boost::none) const |
double | depth () const |
double | inverse_depth () const |
size_t | dim () const |
InverseDepthMeasurement | retract (const gtsam::Vector &d) const |
gtsam::Vector1 | localCoordinates (const InverseDepthMeasurement &T2) const |
void | print (const std::string &s=std::string()) const |
bool | equals (const InverseDepthMeasurement &s, double tol=1e-9) const |
Static Public Member Functions | |
static size_t | Dim () |
Optimizable inverse depth parameterization for a landmark point using a (u,v) image space measurement and the associated camera pose for the measurement along with the camera intrinsics matrix to be able to backproject the inverse depth point to a 3d point.
|
inline |
|
inline |
|
inline |
|
inlinestatic |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |