Skip to content

Commit

Permalink
Fix naming conventions
Browse files Browse the repository at this point in the history
  • Loading branch information
ymd-stella committed Apr 23, 2022
1 parent d4adda8 commit f5cbbf5
Show file tree
Hide file tree
Showing 32 changed files with 197 additions and 197 deletions.
10 changes: 5 additions & 5 deletions src/pangolin_viewer/viewer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ void viewer::draw_keyframes() {
if (!keyfrm || keyfrm->will_be_erased()) {
continue;
}
draw_camera(keyfrm->get_cam_pose_inv(), w);
draw_camera(keyfrm->get_pose_wc(), w);
}
}

Expand All @@ -232,7 +232,7 @@ void viewer::draw_keyframes() {
continue;
}

const stella_vslam::Vec3_t cam_center_1 = keyfrm->get_cam_center();
const stella_vslam::Vec3_t cam_center_1 = keyfrm->get_trans_wc();

// covisibility graph
const auto covisibilities = keyfrm->graph_node_->get_covisibilities_over_weight(100);
Expand All @@ -244,15 +244,15 @@ void viewer::draw_keyframes() {
if (covisibility->id_ < keyfrm->id_) {
continue;
}
const stella_vslam::Vec3_t cam_center_2 = covisibility->get_cam_center();
const stella_vslam::Vec3_t cam_center_2 = covisibility->get_trans_wc();
draw_edge(cam_center_1, cam_center_2);
}
}

// spanning tree
auto spanning_parent = keyfrm->graph_node_->get_spanning_parent();
if (spanning_parent) {
const stella_vslam::Vec3_t cam_center_2 = spanning_parent->get_cam_center();
const stella_vslam::Vec3_t cam_center_2 = spanning_parent->get_trans_wc();
draw_edge(cam_center_1, cam_center_2);
}

Expand All @@ -265,7 +265,7 @@ void viewer::draw_keyframes() {
if (loop_edge->id_ < keyfrm->id_) {
continue;
}
const stella_vslam::Vec3_t cam_center_2 = loop_edge->get_cam_center();
const stella_vslam::Vec3_t cam_center_2 = loop_edge->get_trans_wc();
draw_edge(cam_center_1, cam_center_2);
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/socket_publisher/data_serializer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ std::string data_serializer::serialize_as_protobuf(const std::vector<std::shared
}

const auto id = keyfrm->id_;
const auto pose = keyfrm->get_cam_pose();
const auto pose = keyfrm->get_pose_cw();
const auto pose_hash = get_mat_hash(pose); // get zipped code (likely hash)

next_keyframe_hash_map[id] = pose_hash;
Expand Down
38 changes: 19 additions & 19 deletions src/stella_vslam/data/frame.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,39 +21,39 @@ frame::frame(const double timestamp, camera::base* camera, feature::orb_params*
// Initialize association with 3D points
landmarks_(std::vector<std::shared_ptr<landmark>>(frm_obs_.num_keypts_, nullptr)) {}

void frame::set_cam_pose(const Mat44_t& cam_pose_cw) {
void frame::set_pose_cw(const Mat44_t& pose_cw) {
cam_pose_cw_is_valid_ = true;
cam_pose_cw_ = cam_pose_cw;
pose_cw_ = pose_cw;
update_pose_params();
}

void frame::set_cam_pose(const g2o::SE3Quat& cam_pose_cw) {
set_cam_pose(util::converter::to_eigen_mat(cam_pose_cw));
void frame::set_pose_cw(const g2o::SE3Quat& pose_cw) {
set_pose_cw(util::converter::to_eigen_mat(pose_cw));
}

Mat44_t frame::get_cam_pose() const {
return cam_pose_cw_;
Mat44_t frame::get_pose_cw() const {
return pose_cw_;
}

Mat44_t frame::get_cam_pose_inv() const {
Mat44_t cam_pose_wc = Mat44_t::Identity();
cam_pose_wc.block<3, 3>(0, 0) = rot_wc_;
cam_pose_wc.block<3, 1>(0, 3) = cam_center_;
return cam_pose_wc;
Mat44_t frame::get_pose_wc() const {
Mat44_t pose_wc = Mat44_t::Identity();
pose_wc.block<3, 3>(0, 0) = rot_wc_;
pose_wc.block<3, 1>(0, 3) = trans_wc_;
return pose_wc;
}

void frame::update_pose_params() {
rot_cw_ = cam_pose_cw_.block<3, 3>(0, 0);
rot_cw_ = pose_cw_.block<3, 3>(0, 0);
rot_wc_ = rot_cw_.transpose();
trans_cw_ = cam_pose_cw_.block<3, 1>(0, 3);
cam_center_ = -rot_cw_.transpose() * trans_cw_;
trans_cw_ = pose_cw_.block<3, 1>(0, 3);
trans_wc_ = -rot_cw_.transpose() * trans_cw_;
}

Vec3_t frame::get_cam_center() const {
return cam_center_;
Vec3_t frame::get_trans_wc() const {
return trans_wc_;
}

Mat33_t frame::get_rotation_inv() const {
Mat33_t frame::get_rot_wc() const {
return rot_wc_;
}

Expand All @@ -74,7 +74,7 @@ bool frame::can_observe(const std::shared_ptr<landmark>& lm, const float ray_cos
return false;
}

const Vec3_t cam_to_lm_vec = pos_w - cam_center_;
const Vec3_t cam_to_lm_vec = pos_w - trans_wc_;
const auto cam_to_lm_dist = cam_to_lm_vec.norm();
if (!lm->is_inside_in_orb_scale(cam_to_lm_dist)) {
return false;
Expand All @@ -95,7 +95,7 @@ std::vector<unsigned int> frame::get_keypoints_in_cell(const float ref_x, const
}

Vec3_t frame::triangulate_stereo(const unsigned int idx) const {
return data::triangulate_stereo(camera_, rot_wc_, cam_center_, frm_obs_, idx);
return data::triangulate_stereo(camera_, rot_wc_, trans_wc_, frm_obs_, idx);
}

} // namespace data
Expand Down
22 changes: 11 additions & 11 deletions src/stella_vslam/data/frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,42 +61,42 @@ class frame {

/**
* Set camera pose and refresh rotation and translation
* @param cam_pose_cw
* @param pose_cw
*/
void set_cam_pose(const Mat44_t& cam_pose_cw);
void set_pose_cw(const Mat44_t& pose_cw);

/**
* Set camera pose and refresh rotation and translation
* @param cam_pose_cw
* @param pose_cw
*/
void set_cam_pose(const g2o::SE3Quat& cam_pose_cw);
void set_pose_cw(const g2o::SE3Quat& pose_cw);

/**
* Get camera pose
*/
Mat44_t get_cam_pose() const;
Mat44_t get_pose_cw() const;

/**
* Get the inverse of the camera pose
*/
Mat44_t get_cam_pose_inv() const;
Mat44_t get_pose_wc() const;

/**
* Update rotation and translation using cam_pose_cw_
* Update rotation and translation using pose_cw_
*/
void update_pose_params();

/**
* Get camera center
* @return
*/
Vec3_t get_cam_center() const;
Vec3_t get_trans_wc() const;

/**
* Get inverse of rotation
* @return
*/
Mat33_t get_rotation_inv() const;
Mat33_t get_rot_wc() const;

/**
* Returns true if BoW has been computed.
Expand Down Expand Up @@ -167,7 +167,7 @@ class frame {

//! camera pose: world -> camera
bool cam_pose_cw_is_valid_ = false;
Mat44_t cam_pose_cw_;
Mat44_t pose_cw_;

//! reference keyframe for tracking
std::shared_ptr<keyframe> ref_keyfrm_ = nullptr;
Expand All @@ -181,7 +181,7 @@ class frame {
//! rotation: camera -> world
Mat33_t rot_wc_;
//! translation: camera -> world
Vec3_t cam_center_;
Vec3_t trans_wc_;
};

} // namespace data
Expand Down
6 changes: 3 additions & 3 deletions src/stella_vslam/data/frame_statistics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ namespace data {

void frame_statistics::update_frame_statistics(const data::frame& frm, const bool is_lost) {
if (frm.cam_pose_cw_is_valid_) {
const Mat44_t rel_cam_pose_from_ref_keyfrm = frm.cam_pose_cw_ * frm.ref_keyfrm_->get_cam_pose_inv();
const Mat44_t rel_cam_pose_from_ref_keyfrm = frm.pose_cw_ * frm.ref_keyfrm_->get_pose_wc();

frm_ids_of_ref_keyfrms_[frm.ref_keyfrm_].push_back(frm.id_);

Expand Down Expand Up @@ -44,14 +44,14 @@ void frame_statistics::replace_reference_keyframe(const std::shared_ptr<data::ke
assert(*ref_keyfrms_.at(frm_id) == *old_keyfrm);

// Get pose and relative pose of the old keyframe
const Mat44_t old_ref_cam_pose_cw = old_keyfrm->get_cam_pose();
const Mat44_t old_ref_cam_pose_cw = old_keyfrm->get_pose_cw();
const Mat44_t old_rel_cam_pose_cr = rel_cam_poses_from_ref_keyfrms_.at(frm_id);

// Replace pointer of the keyframe to new_keyfrm
ref_keyfrms_.at(frm_id) = new_keyfrm;

// Update relative pose
const Mat44_t new_ref_cam_pose_cw = new_keyfrm->get_cam_pose();
const Mat44_t new_ref_cam_pose_cw = new_keyfrm->get_pose_cw();
const Mat44_t new_rel_cam_pose_cr = old_rel_cam_pose_cr * old_ref_cam_pose_cw * new_ref_cam_pose_cw.inverse();
rel_cam_poses_from_ref_keyfrms_.at(frm_id) = new_rel_cam_pose_cr;
}
Expand Down
72 changes: 36 additions & 36 deletions src/stella_vslam/data/keyframe.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,21 +21,21 @@ keyframe::keyframe(const frame& frm)
frm_obs_(frm.frm_obs_), markers_2d_(frm.markers_2d_),
bow_vec_(frm.bow_vec_), bow_feat_vec_(frm.bow_feat_vec_),
landmarks_(frm.landmarks_) {
// set pose parameters (cam_pose_wc_, cam_center_) using frm.cam_pose_cw_
set_cam_pose(frm.cam_pose_cw_);
// set pose parameters (pose_wc_, trans_wc_) using frm.pose_cw_
set_pose_cw(frm.pose_cw_);
}

keyframe::keyframe(const unsigned int id, const unsigned int src_frm_id, const double timestamp,
const Mat44_t& cam_pose_cw, camera::base* camera,
const Mat44_t& pose_cw, camera::base* camera,
const feature::orb_params* orb_params, const frame_observation& frm_obs,
const bow_vector& bow_vec, const bow_feature_vector& bow_feat_vec)
: id_(id), src_frm_id_(src_frm_id),
timestamp_(timestamp), camera_(camera),
orb_params_(orb_params), frm_obs_(frm_obs),
bow_vec_(bow_vec), bow_feat_vec_(bow_feat_vec),
landmarks_(std::vector<std::shared_ptr<landmark>>(frm_obs_.num_keypts_, nullptr)) {
// set pose parameters (cam_pose_wc_, cam_center_) using cam_pose_cw_
set_cam_pose(cam_pose_cw);
// set pose parameters (pose_wc_, trans_wc_) using pose_cw_
set_pose_cw(pose_cw);

// The following process needs to take place:
// should set the pointers of landmarks_ using add_landmark()
Expand All @@ -56,13 +56,13 @@ std::shared_ptr<keyframe> keyframe::make_keyframe(const frame& frm) {

std::shared_ptr<keyframe> keyframe::make_keyframe(
const unsigned int id, const unsigned int src_frm_id, const double timestamp,
const Mat44_t& cam_pose_cw, camera::base* camera,
const Mat44_t& pose_cw, camera::base* camera,
const feature::orb_params* orb_params, const frame_observation& frm_obs,
const bow_vector& bow_vec, const bow_feature_vector& bow_feat_vec) {
auto ptr = std::allocate_shared<keyframe>(
Eigen::aligned_allocator<keyframe>(),
id, src_frm_id, timestamp,
cam_pose_cw, camera, orb_params,
pose_cw, camera, orb_params,
frm_obs, bow_vec, bow_feat_vec);
// covisibility graph node (connections is not assigned yet)
ptr->graph_node_ = stella_vslam::make_unique<graph_node>(ptr, false);
Expand Down Expand Up @@ -101,8 +101,8 @@ nlohmann::json keyframe::to_json() const {
{"cam", camera_->name_},
{"orb_params", orb_params_->name_},
// camera pose
{"rot_cw", convert_rotation_to_json(cam_pose_cw_.block<3, 3>(0, 0))},
{"trans_cw", convert_translation_to_json(cam_pose_cw_.block<3, 1>(0, 3))},
{"rot_cw", convert_rotation_to_json(pose_cw_.block<3, 3>(0, 0))},
{"trans_cw", convert_translation_to_json(pose_cw_.block<3, 1>(0, 3))},
// features and observations
{"n_keypts", frm_obs_.num_keypts_},
{"undist_keypts", convert_undistorted_to_json(frm_obs_.undist_keypts_)},
Expand All @@ -116,47 +116,47 @@ nlohmann::json keyframe::to_json() const {
{"loop_edges", loop_edge_ids}};
}

void keyframe::set_cam_pose(const Mat44_t& cam_pose_cw) {
void keyframe::set_pose_cw(const Mat44_t& pose_cw) {
std::lock_guard<std::mutex> lock(mtx_pose_);
cam_pose_cw_ = cam_pose_cw;
pose_cw_ = pose_cw;

const Mat33_t rot_cw = cam_pose_cw_.block<3, 3>(0, 0);
const Vec3_t trans_cw = cam_pose_cw_.block<3, 1>(0, 3);
const Mat33_t rot_cw = pose_cw_.block<3, 3>(0, 0);
const Vec3_t trans_cw = pose_cw_.block<3, 1>(0, 3);
const Mat33_t rot_wc = rot_cw.transpose();
cam_center_ = -rot_wc * trans_cw;
trans_wc_ = -rot_wc * trans_cw;

cam_pose_wc_ = Mat44_t::Identity();
cam_pose_wc_.block<3, 3>(0, 0) = rot_wc;
cam_pose_wc_.block<3, 1>(0, 3) = cam_center_;
pose_wc_ = Mat44_t::Identity();
pose_wc_.block<3, 3>(0, 0) = rot_wc;
pose_wc_.block<3, 1>(0, 3) = trans_wc_;
}

void keyframe::set_cam_pose(const g2o::SE3Quat& cam_pose_cw) {
set_cam_pose(util::converter::to_eigen_mat(cam_pose_cw));
void keyframe::set_pose_cw(const g2o::SE3Quat& pose_cw) {
set_pose_cw(util::converter::to_eigen_mat(pose_cw));
}

Mat44_t keyframe::get_cam_pose() const {
Mat44_t keyframe::get_pose_cw() const {
std::lock_guard<std::mutex> lock(mtx_pose_);
return cam_pose_cw_;
return pose_cw_;
}

Mat44_t keyframe::get_cam_pose_inv() const {
Mat44_t keyframe::get_pose_wc() const {
std::lock_guard<std::mutex> lock(mtx_pose_);
return cam_pose_wc_;
return pose_wc_;
}

Vec3_t keyframe::get_cam_center() const {
Vec3_t keyframe::get_trans_wc() const {
std::lock_guard<std::mutex> lock(mtx_pose_);
return cam_center_;
return trans_wc_;
}

Mat33_t keyframe::get_rotation() const {
Mat33_t keyframe::get_rot_cw() const {
std::lock_guard<std::mutex> lock(mtx_pose_);
return cam_pose_cw_.block<3, 3>(0, 0);
return pose_cw_.block<3, 3>(0, 0);
}

Vec3_t keyframe::get_translation() const {
Vec3_t keyframe::get_trans_cw() const {
std::lock_guard<std::mutex> lock(mtx_pose_);
return cam_pose_cw_.block<3, 1>(0, 3);
return pose_cw_.block<3, 1>(0, 3);
}

bool keyframe::bow_is_available() const {
Expand Down Expand Up @@ -258,28 +258,28 @@ std::vector<unsigned int> keyframe::get_keypoints_in_cell(const float ref_x, con
}

Vec3_t keyframe::triangulate_stereo(const unsigned int idx) const {
Mat44_t cam_pose_wc;
Mat44_t pose_wc;
{
std::lock_guard<std::mutex> lock(mtx_pose_);
cam_pose_wc = cam_pose_wc_;
pose_wc = pose_wc_;
}
return data::triangulate_stereo(camera_, cam_pose_wc.block<3, 3>(0, 0), cam_pose_wc.block<3, 1>(0, 3), frm_obs_, idx);
return data::triangulate_stereo(camera_, pose_wc.block<3, 3>(0, 0), pose_wc.block<3, 1>(0, 3), frm_obs_, idx);
}

float keyframe::compute_median_depth(const bool abs) const {
std::vector<std::shared_ptr<landmark>> landmarks;
Mat44_t cam_pose_cw;
Mat44_t pose_cw;
{
std::lock_guard<std::mutex> lock1(mtx_observations_);
std::lock_guard<std::mutex> lock2(mtx_pose_);
landmarks = landmarks_;
cam_pose_cw = cam_pose_cw_;
pose_cw = pose_cw_;
}

std::vector<float> depths;
depths.reserve(frm_obs_.num_keypts_);
const Vec3_t rot_cw_z_row = cam_pose_cw.block<1, 3>(2, 0);
const float trans_cw_z = cam_pose_cw(2, 3);
const Vec3_t rot_cw_z_row = pose_cw.block<1, 3>(2, 0);
const float trans_cw_z = pose_cw(2, 3);

for (const auto& lm : landmarks) {
if (!lm) {
Expand Down
Loading

0 comments on commit f5cbbf5

Please sign in to comment.