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

Use imu rotation to estimate orientation of odometry #623

Draft
wants to merge 3 commits into
base: main
Choose a base branch
from
Draft
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
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,11 @@

#include <biped_interfaces/msg/phase.hpp>
#include <bitbots_utils/utils.hpp>
#include <geometry_msgs/msg/quaternion_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <std_msgs/msg/char.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
Expand All @@ -31,11 +33,12 @@ class MotionOdometry : public rclcpp::Node {
rclcpp::Time current_support_state_time_{rclcpp::Time(0, 0, RCL_ROS_TIME)};
nav_msgs::msg::Odometry current_odom_msg_;
tf2::Transform odometry_to_support_foot_;
std::string base_link_frame_, r_sole_frame_, l_sole_frame_, odom_frame_;
std::string base_link_frame_, r_sole_frame_, l_sole_frame_, odom_frame_, imu_frame_;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_odometry_;
rclcpp::Subscription<biped_interfaces::msg::Phase>::SharedPtr walk_support_state_sub_;
rclcpp::Subscription<biped_interfaces::msg::Phase>::SharedPtr kick_support_state_sub_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_subscriber_;
rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr imu_subscriber_;

// Declare parameter listener and struct from the generate_parameter_library
motion_odometry::ParamListener param_listener_;
Expand All @@ -44,6 +47,7 @@ class MotionOdometry : public rclcpp::Node {

void supportCallback(const biped_interfaces::msg::Phase::SharedPtr msg);
void odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg);
void IMUCallback(const sensor_msgs::msg::Imu::SharedPtr msg);

tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;
Expand All @@ -52,6 +56,11 @@ class MotionOdometry : public rclcpp::Node {
std::string previous_support_link_;
std::string current_support_link_;
rclcpp::Time start_time_;

tf2::Quaternion current_imu_orientation_;
tf2::Quaternion initial_imu_transform_;

bool is_initial_transform_set_ = false;
};

} // namespace bitbots_odometry
32 changes: 25 additions & 7 deletions bitbots_navigation/bitbots_odometry/src/motion_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,17 @@ MotionOdometry::MotionOdometry()
this->get_parameter("l_sole_frame", l_sole_frame_);
this->declare_parameter<std::string>("odom_frame", "odom");
this->get_parameter("odom_frame", odom_frame_);
this->declare_parameter<std::string>("imu_frame", "imu_frame");
this->get_parameter("imu_frame", imu_frame_);

walk_support_state_sub_ = this->create_subscription<biped_interfaces::msg::Phase>(
"walk_support_state", 1, std::bind(&MotionOdometry::supportCallback, this, _1));
kick_support_state_sub_ = this->create_subscription<biped_interfaces::msg::Phase>(
"dynamic_kick_support_state", 1, std::bind(&MotionOdometry::supportCallback, this, _1));
odom_subscriber_ = this->create_subscription<nav_msgs::msg::Odometry>(
"walk_engine_odometry", 1, std::bind(&MotionOdometry::odomCallback, this, _1));
imu_subscriber_ = this->create_subscription<sensor_msgs::msg::Imu>("imu/data", 1,
std::bind(&MotionOdometry::IMUCallback, this, _1));

pub_odometry_ = this->create_publisher<nav_msgs::msg::Odometry>("motion_odometry", 1);

Expand Down Expand Up @@ -75,12 +79,10 @@ void MotionOdometry::loop() {
x = x * config_.x_backward_scaling;
}
double y = previous_to_current_support.getOrigin().y() * config_.y_scaling;
double yaw = tf2::getYaw(previous_to_current_support.getRotation()) * config_.yaw_scaling;
previous_to_current_support.setOrigin({x, y, 0});
tf2::Quaternion q;
q.setRPY(0, 0, yaw);
previous_to_current_support.setRotation(q);

odometry_to_support_foot_ = odometry_to_support_foot_ * previous_to_current_support;

} catch (tf2::TransformException &ex) {
RCLCPP_WARN(this->get_logger(), "%s", ex.what());
rclcpp::sleep_for(std::chrono::milliseconds(1000));
Expand All @@ -100,6 +102,9 @@ void MotionOdometry::loop() {
try {
geometry_msgs::msg::TransformStamped current_support_to_base_msg =
tf_buffer_.lookupTransform(previous_support_link_, base_link_frame_, rclcpp::Time(0, 0, RCL_ROS_TIME));
geometry_msgs::msg::TransformStamped imu_to_base_msg =
tf_buffer_.lookupTransform(imu_frame_, base_link_frame_, rclcpp::Time(0, 0, RCL_ROS_TIME));

tf2::Transform current_support_to_base;
tf2::fromMsg(current_support_to_base_msg.transform, current_support_to_base);
double x = current_support_to_base.getOrigin().x();
Expand All @@ -109,10 +114,13 @@ void MotionOdometry::loop() {
x = x * config_.x_backward_scaling;
}
double y = current_support_to_base.getOrigin().y() * config_.y_scaling;
double yaw = tf2::getYaw(current_support_to_base.getRotation()) * config_.yaw_scaling;
current_support_to_base.setOrigin({x, y, current_support_to_base.getOrigin().z()});

tf2::Quaternion q;
q.setRPY(0, 0, yaw);
tf2::Transform imu_to_base;
fromMsg(imu_to_base_msg.transform, imu_to_base);
q = current_imu_orientation_ * initial_imu_transform_ * imu_to_base.getRotation();

current_support_to_base.setOrigin({x, y, current_support_to_base.getOrigin().z()});
current_support_to_base.setRotation(q);

tf2::Transform odom_to_base_link = odometry_to_support_foot_ * current_support_to_base;
Expand Down Expand Up @@ -177,6 +185,16 @@ void MotionOdometry::supportCallback(const biped_interfaces::msg::Phase::SharedP

void MotionOdometry::odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg) { current_odom_msg_ = *msg; }

void MotionOdometry::IMUCallback(const sensor_msgs::msg::Imu::SharedPtr msg) {
tf2::fromMsg(msg->orientation, current_imu_orientation_);
if (is_initial_transform_set_ == false) {
is_initial_transform_set_ = true;
initial_imu_transform_ = current_imu_orientation_;
initial_imu_transform_.setW(-1.0);
initial_imu_transform_.normalize();
}
}

} // namespace bitbots_odometry

int main(int argc, char **argv) {
Expand Down
Loading