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

Overwriting odometry #750

Closed
3 of 24 tasks
paolorugg opened this issue Jun 13, 2021 · 9 comments
Closed
3 of 24 tasks

Overwriting odometry #750

paolorugg opened this issue Jun 13, 2021 · 9 comments

Comments

@paolorugg
Copy link

ISSUE TEMPLATE ver. 0.4.0

  1. Which TurtleBot3 platform do you use?

    • Burger
    • Waffle
    • Waffle Pi
  2. Which ROS is working with TurtleBot3?

    • ROS 1 Kinetic Kame
    • ROS 1 Melodic Morenia
    • ROS 1 Noetic Ninjemys
    • ROS 2 Dashing Diademata
    • ROS 2 Eloquent Elusor
    • ROS 2 Foxy Fitzroy
    • etc (Please specify your ROS Version here)
  3. Which SBC(Single Board Computer) is working on TurtleBot3?

    • Intel Joule 570x
    • Raspberry Pi 3B+
    • Raspberry Pi 4
    • etc (Please specify your SBC here)
  4. Which OS you installed on SBC?

    • Raspbian distributed by ROBOTIS
    • Ubuntu MATE (16.04/18.04/20.04)
    • Ubuntu preinstalled server (18.04/20.04)
    • etc (Please specify your OS here)
  5. Which OS you installed on Remote PC?

    • Ubuntu 16.04 LTS (Xenial Xerus)
    • Ubuntu 18.04 LTS (Bionic Beaver)
    • Ubuntu 20.04 LTS (Focal Fossa)
    • Windows 10
    • MAC OS X (Specify version)
    • etc (Please specify your OS here)
  6. Specify the software and firmware version(Can be found from Bringup messages)

    • Software version: [x.x.x]
    • Firmware version: [x.x.x]
  7. Specify the commands or instructions to reproduce the issue.

    • HERE
  8. Copy and Paste the error messages on terminal.

    • HERE
  9. Please describe the issue in detail.

    • For my project, I was trying to exploit a landmark of known location to impose a precise pose to turtlebot3, thus nullifying the odometry error that naturally accumulates during motion. I have built a ros2 node that publishes an odometry message on /odom topic, and it works, but the problem is that when it stops sending messages to /odom, the pose on /odom goes back to the one estimated ignoring my input. In my idea instead it should go on estimating its pose but starting from the pose i provided.
      I have also searched for a ros2 service to be used, but couldn't find any. Maybe there is something I'm missing on how turtlebot3 provides its position. If you could help me on this, it would be really appreciated.
@ROBOTIS-Will
Copy link
Contributor

Hi @paolorugg
The odometry of TurtleBot3 in ROS2 is calculated in the turtlebot3_ros node as below at the startup of robot.launch.py.
https://github.com/ROBOTIS-GIT/turtlebot3/blob/foxy-devel/turtlebot3_node/src/odometry.cpp#L217

Since robot_pose_[] is a private variable of the Odometry class, you'll need to create a new function in order to update the value.

@paolorugg
Copy link
Author

paolorugg commented Jun 14, 2021

Thank you for the fast reply. I have given a look at the code, and now my question is: will it be enough for my function to over write robot_pose_[] and reset to 0 values diff_joint_positions_[], or are there more variables to be reset? Because for the moment I would like to change only the position of the robot, and keep the estimated orientation. Thanks again.

@ROBOTIS-Will
Copy link
Contributor

@paolorugg
Copy link
Author

Thank you very much for the help, in the end I even integrated overwriting the orientation. Much appreciated

@adbidwai
Copy link

What about overwriting odometry of Turtlebot3 if I am using ROS1?

@sudar1220
Copy link

Hi @paolorugg,
Can you share your solution? I was looking for the same thing with resetting the odometery with a known pose and orientation.
I am also using ROS2 Foxy on TB3 WafflePi.
Appreciate any help in this regards,
Thanks in advance

@sudar1220
Copy link

@adbidwai

What about overwriting odometry of Turtlebot3 if I am using ROS1?

maybe this is useful for you: https://github.com/MikeHallettUK/RosRobotics/blob/master/resetodom.py
I think this is for ROS1, but I am not sure exactly how it works, I did find this when I was looking how to reset odom in ROS2

@paolorugg
Copy link
Author

Hi @paolorugg, Can you share your solution? I was looking for the same thing with resetting the odometery with a known pose and orientation. I am also using ROS2 Foxy on TB3 WafflePi. Appreciate any help in this regards, Thanks in advance

Yeah sure. For an immediate solution you can download my_turtlebot3_node package from my github, that is a modified version of the turtlebot3 node. Then you have to use it instead of the official one.
I modified it to overwrite odometry by publishing a Point message (technically speaking it's a worng messaage type, but I was in the beginning) on a topic called '/pose_relocalization'. The message should be [x in meters; y in meters; angle or rotation in radians]. Once a message is sent, my modified turtlebot node reads it and over write the odometry.
Otherwise you can take inspiration and find your way of doing it, publishing a coherent message type for example.

I hope this helps you!

@spolstra
Copy link

spolstra commented Oct 10, 2023

Hi,

I'm new to ros and ran into the same problem setting up some turtlebots for a lab. The latest firmware update fixed the 'teleporting' problem on our foxy installation but the turtlebots with the raspberry pi4 boards would have very large initial odometer values as already mentioned above. I noticed that some members in the Odometry class where not initialized so I changed the following lines in the turtlebot3_node odometry.hpp file from:

  std::array<double, 2> diff_joint_positions_;
  double imu_angle_;

  std::array<double, 3> robot_pose_;
  std::array<double, 3> robot_vel_;

to:

  std::array<double, 2> diff_joint_positions_ = {0.0, 0.0};
  double imu_angle_ = 0.0;

  std::array<double, 3> robot_pose_ = {0.0, 0.0, 0.0};
  std::array<double, 3> robot_vel_ = {0.0, 0.0, 0.0};

And then recompiling the turtlebot3_node with:

cd ~/turtlebot3_ws && colcon build --packages-select turtlebot3_node --symlink-install

Now the turtlebot always starts with values that are very close to zero, which is good enough for our lab. My assumption is that the robot_pose is used as the starting value which might explain why they are not exactly zero, but I don't know enough about ros to be sure if that is actually the case.

Hope this helps

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

5 participants