ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The base_link
frame is the root of your robot kinematic tree. Given a particular kinematic model and a particular configuration of your robot you can determine the relative position of all your robot bodies.
When your robot is made of solid bodies linked together by joints whom parameters are accurately known this problem is quite trivial and, in particular, is solved by the robot_state_publisher node. However, when it comes to the "map" and "odom" frame the problem is totally different. These two frames meaning is defined in REP 105. They define the position of the robot in the "world" frame.
Here you have two cases:
static_transform_publisher
to stream this relative position.You usually have two "levels" of localisation: - a local method which drifts (integrating the command for instance) - a global one which tries to estimate the robot position from exterior information such as the environment (SLAM algorithms, GPS may enter this category).
The local method will define the odom frame (this frames drifts but the position never jump from one position to another one which is good when you need a reference value for your command) whereas the map frame should be accurate anytime but may jump from a position to another one which may produce very high velocities if you try to close the loop on this data.
One should always have: map -> odom -> base_link
If you don't have components to estimate all the frames it is ok to set some of these frames relative information to the identity. At this point the best strategy really depends on your robot and your application.
To conclude, tf
is not a tool which only broadcasts frame position estimated from the robot model and its configuration, this is only one possibility offered by ROS. It makes sense for most of the robots to do so to estimate the robot bodies relative position but it makes no sense for the other frames. Therefore, adding odom or map in your robot model is a bad idea unless it is a fixed base robot. Even in this case, IMHO it is better to use a static_transform_publisher
as you may want at some point to relocate your robot at a different location w.r.t to your world frame. Also, editing 3rd party package is a bad practice, if you use a model from a ROS package, editing the xacro to fit your own need is a bad practice.
2 | No.2 Revision |
The base_link
frame is the root of your robot kinematic tree. Given a particular kinematic model and a particular configuration of your robot you can determine the relative position of all your robot bodies.
When your robot is made of solid bodies linked together by joints whom parameters are accurately known this problem is quite trivial and, in particular, is solved by the robot_state_publisher node. However, when it comes to the "map" and "odom" frame the problem is totally different. These two frames meaning is defined in REP 105. They define the position of the robot in the "world" frame.
Here you have two cases:
static_transform_publisher
to stream this relative position.You usually have two "levels" of localisation:
- localisation:
The local method will define the odom frame (this frames drifts but the position never jump from one position to another one which is good when you need a reference value for your command) whereas the map frame should be accurate anytime but may jump from a position to another one which may produce very high velocities if you try to close the loop on this data.
One should always have: map -> odom -> base_link
If you don't have components to estimate all the frames it is ok to set some of these frames relative information to the identity. At this point the best strategy really depends on your robot and your application.
To conclude, tf
is not a tool which only broadcasts frame position estimated from the robot model and its configuration, this is only one possibility offered by ROS. It makes sense for most of the robots to do so to estimate the robot bodies relative position but it makes no sense for the other frames. Therefore, adding odom or map in your robot model is a bad idea unless it is a fixed base robot. Even in this case, IMHO it is better to use a static_transform_publisher
as you may want at some point to relocate your robot at a different location w.r.t to your world frame. Also, editing 3rd party package is a bad practice, if you use a model from a ROS package, editing the xacro to fit your own need is a bad practice.
3 | No.3 Revision |
The base_link
frame is the root of your robot kinematic tree. Given a particular kinematic model and a particular configuration of your robot you can determine the relative position of all your robot bodies.
When your robot is made of solid bodies linked together by joints whom parameters are accurately known known, this problem is quite trivial and, in trivial. In particular, it is solved by the robot_state_publisher node. However, when it comes to the "map" and "odom" frame the problem is totally different. These two frames meaning is defined in REP 105. They define the position of the robot in the "world" frame.
Here you have two cases:
static_transform_publisher
to stream this relative position.You usually have two "levels" of localisation:
The local method will define the odom frame (this frames drifts but the position never jump from one position to another one which is good when you need a reference value for your command) whereas the map frame should be accurate anytime but may jump from a position to another one which may produce very high velocities if you try to close the loop on this data.
One should always have: map -> odom -> base_link
If you don't have components to estimate all the frames it is ok to set some of these frames relative information to the identity. At this point the best strategy really depends on your robot and your application.
To conclude, tf
is not a tool which only broadcasts frame position estimated from the robot model and its configuration, this is only one possibility offered by ROS. It makes sense for most of the robots to do so to estimate the robot bodies relative position but it makes no sense for the other frames. Therefore, adding odom or map in your robot model is a bad idea unless it is a fixed base robot. Even in this case, IMHO it is better to use a static_transform_publisher
as you may want at some point to relocate your robot at a different location w.r.t to your world frame. Also, editing 3rd party package is a bad practice, if you use a model from a ROS package, editing the xacro to fit your own need is a bad practice.
4 | No.4 Revision |
The base_link
frame is the root of your robot kinematic tree. Given a particular kinematic model and a particular configuration of your robot you can determine the relative position of all your robot bodies.
When your robot is made of solid bodies linked together by joints whom parameters are accurately known, this problem is quite trivial. In particular, it is solved by the robot_state_publisher node. However, when it comes to the "map" and "odom" frame the problem is totally different. These two frames meaning is defined in REP 105. They define the position of the robot in the "world" frame.
Here you have two cases:
static_transform_publisher
to stream this relative position.You usually have two "levels" of localisation:
The local method will define the odom frame (this frames drifts but the position never jump from one position to another one which is good when you need a reference value for your command) whereas the map frame should be accurate anytime but may jump from a position to another one which may produce very high velocities if you try to close the loop on this data.
One should always have: map -> odom -> base_link
If you don't have components to estimate all the frames it is ok to set some of these frames relative information to the identity. At this point the best strategy really depends on your robot and your application.
To conclude, tf
is not a tool which only broadcasts frame position estimated from the robot model and its configuration, this is only one possibility offered by ROS. It makes sense for most of the robots to do so to estimate the robot bodies relative position but it makes no sense for the other frames. Therefore, adding odom or map in your robot model is a bad idea unless it is a fixed base robot. Even in this case, IMHO it is better to use a static_transform_publisher
as you may want at some point to relocate your robot at a different location w.r.t to your world frame. Also, editing 3rd party package is a bad practice, if you use a model from a ROS package, editing the xacro to fit your own need is a bad practice.
5 | No.5 Revision |
The base_link
frame is the root of your robot kinematic tree. Given a particular kinematic model and a particular configuration of your robot you can determine the relative position of all your robot bodies.
When your robot is made of solid bodies linked together by joints whom parameters are accurately known, this problem is quite trivial. In particular, it is solved by the robot_state_publisher node. However, when it comes to the "map" and "odom" frame the problem is totally different. These two frames meaning is defined in REP 105. They define the position of the robot in the "world" frame.
Here you have two cases:
static_transform_publisher
to stream this relative position.You usually have two "levels" of localisation:
The local method will define the odom frame (this frames drifts but the position never jump from one position to another one which is good when you need a reference value for your command) whereas the map frame should be accurate anytime but may jump from a position to another one which may produce very high velocities if you try to close the loop on this data.
One should always have: map -> odom -> base_link
If you don't have components to estimate all the frames it is ok to set some of these frames relative information to the identity. At this point the best strategy really depends on your robot and your application.
To conclude, tf
is not a tool which only broadcasts frame position estimated from the robot model and its configuration, this is only one possibility offered by ROS. It makes sense for most of the robots to do so to estimate the robot bodies relative position but it makes no sense for the other frames. Therefore, adding odom or map in your robot model is a bad idea unless it is a fixed base robot. Even in this case, IMHO it is better to use a static_transform_publisher
as you may want at some point to relocate your robot at a different location w.r.t to your world frame. Also, editing 3rd party package is a bad practice, if you use a model from a ROS package, editing the xacro to fit your own need is a bad practice.