Skip to content
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

Fix parameter name and default value for base_link #149

Merged
merged 1 commit into from
Jul 23, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ stella_vslam_ros uses submodules. Clone it with `git clone --recursive` or downl

- `odom_frame`
- `map_frame`
- `base_link`
- `robot_base_frame`
- `camera_frame`
- `publish_tf`
- `publish_pointcloud`
Expand Down
16 changes: 8 additions & 8 deletions src/stella_vslam_ros.cc
Original file line number Diff line number Diff line change
Expand Up @@ -125,8 +125,8 @@ void system::setParams() {
map_frame_ = std::string("map");
private_nh_.param("map_frame", map_frame_, map_frame_);

base_link_ = std::string("base_footprint");
private_nh_.param("base_link", base_link_, base_link_);
robot_base_frame_ = std::string("base_link");
private_nh_.param("robot_base_frame", robot_base_frame_, robot_base_frame_);

camera_frame_ = std::string("camera_frame");
private_nh_.param("camera_frame", camera_frame_, camera_frame_);
Expand Down Expand Up @@ -178,12 +178,12 @@ void system::init_pose_callback(
return;
}

Eigen::Affine3d base_link_to_camera_affine;
Eigen::Affine3d robot_base_frame_to_camera_affine;
try {
auto base_link_to_camera = tf_->lookupTransform(
base_link_, camera_optical_frame_, msg->header.stamp,
auto robot_base_frame_to_camera = tf_->lookupTransform(
robot_base_frame_, camera_optical_frame_, msg->header.stamp,
ros::Duration(0.0));
base_link_to_camera_affine = tf2::transformToEigen(base_link_to_camera.transform);
robot_base_frame_to_camera_affine = tf2::transformToEigen(robot_base_frame_to_camera.transform);
}
catch (tf2::TransformException& ex) {
ROS_ERROR("Transform failed: %s", ex.what());
Expand All @@ -194,11 +194,11 @@ void system::init_pose_callback(
// rot_cv_to_ros_map_frame: T(map_cv -> map)
// map_to_initialpose_frame_affine: T(map -> `msg->header.frame_id`)
// initialpose_affine: T(`msg->header.frame_id` -> base_link)
// base_link_to_camera_affine: T(base_link -> camera_link)
// robot_base_frame_to_camera_affine: T(base_link -> camera_link)
// The flow of the transformation is as follows:
// map_cv -> map -> `msg->header.frame_id` -> base_link -> camera_link
Eigen::Matrix4d cam_pose_cv = (rot_ros_to_cv_map_frame_.inverse() * map_to_initialpose_frame_affine
* initialpose_affine * base_link_to_camera_affine)
* initialpose_affine * robot_base_frame_to_camera_affine)
.matrix();

const Eigen::Vector3d normal_vector = (Eigen::Vector3d() << 0., 1., 0.).finished();
Expand Down
7 changes: 5 additions & 2 deletions src/stella_vslam_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,11 @@ class system {
ros::Publisher keyframes_2d_pub_;
ros::Subscriber init_pose_sub_;
std::shared_ptr<tf2_ros::TransformBroadcaster> map_to_odom_broadcaster_;
std::string odom_frame_, map_frame_, base_link_;
std::string camera_frame_, camera_optical_frame_;
std::string odom_frame_;
std::string map_frame_;
std::string robot_base_frame_;
std::string camera_frame_;
std::string camera_optical_frame_;
std::unique_ptr<tf2_ros::Buffer> tf_;
std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
bool publish_tf_;
Expand Down