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

no costmap when using SLAM with turtlebot3 #1007

Open
wants to merge 1 commit into
base: humble-devel
Choose a base branch
from

Conversation

aleks9822
Copy link

There is no generated costmap if you want use slam with created map. The reason is, that there are no start values for odometry. This is changed in this pull request.

When running:
ros2 launch turtlebot3_bringup robot.launch.py
ros2 launch turtlebot3_navigation2 navigation2.launch.py map:=$HOME/map.yaml
Error message:
Sensor origin at (7263490040.02, -5.51) is out of map bounds (-8589934592.00, -7.00) to (-8589934589.02, -4.03). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920741.741098784] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51 0.18) is out of map bounds (-8589934592.00, -7.00, 0.00) to (-8589934589.02, -4.03, 0.78). The costmap cannot raytrace for it.
[component_container_isolated-1] [INFO] [1702920741.774218899] [velocity_smoother]: Running Nav2 LifecycleNode rcl preshutdown (velocity_smoother)
[component_container_isolated-1] [INFO] [1702920741.774267537] [velocity_smoother]: Deactivating
[component_container_isolated-1] [INFO] [1702920741.774277669] [velocity_smoother]: Destroying bond (velocity_smoother) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.774289027] [velocity_smoother]: Cleaning up
[component_container_isolated-1] [INFO] [1702920741.774296671] [velocity_smoother]: Destroying bond (velocity_smoother) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.774299312] [waypoint_follower]: Running Nav2 LifecycleNode rcl preshutdown (waypoint_follower)
[component_container_isolated-1] [INFO] [1702920741.774305420] [waypoint_follower]: Deactivating
[component_container_isolated-1] [INFO] [1702920741.774309413] [waypoint_follower]: Destroying bond (waypoint_follower) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.774315230] [waypoint_follower]: Cleaning up
[component_container_isolated-1] [INFO] [1702920741.776827941] [waypoint_follower]: Destroying bond (waypoint_follower) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.776838101] [behavior_server]: Running Nav2 LifecycleNode rcl preshutdown (behavior_server)
[component_container_isolated-1] [INFO] [1702920741.776845997] [behavior_server]: Deactivating
[component_container_isolated-1] [INFO] [1702920741.776858444] [behavior_server]: Destroying bond (behavior_server) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.776868640] [behavior_server]: Cleaning up
[component_container_isolated-1] [INFO] [1702920741.778909745] [behavior_server]: Destroying bond (behavior_server) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.778917544] [bt_navigator]: Running Nav2 LifecycleNode rcl preshutdown (bt_navigator)
[component_container_isolated-1] [INFO] [1702920741.778924289] [bt_navigator]: Deactivating
[component_container_isolated-1] [INFO] [1702920741.778929648] [bt_navigator]: Destroying bond (bt_navigator) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.778937413] [bt_navigator]: Cleaning up
[component_container_isolated-1] [INFO] [1702920741.843219311] [bt_navigator]: Completed Cleaning up
[component_container_isolated-1] [INFO] [1702920741.843243327] [bt_navigator]: Destroying bond (bt_navigator) to lifecycle manager.
[component_container_isolated-1] [INFO] [1702920741.843248385] [global_costmap.global_costmap]: Running Nav2 LifecycleNode rcl preshutdown (global_costmap)
[component_container_isolated-1] [INFO] [1702920741.843256277] [global_costmap.global_costmap]: Deactivating
[component_container_isolated-1] [WARN] [1702920741.941112951] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[component_container_isolated-1] [WARN] [1702920741.941126592] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51) is out of map bounds (-8697308774.40, -7.00) to (-8697308771.42, -4.03). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920741.941153196] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51 0.18) is out of map bounds (-8697308774.40, -7.00, 0.00) to (-8697308771.42, -4.03, 0.78). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920742.141190099] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[component_container_isolated-1] [WARN] [1702920742.141237432] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51) is out of map bounds (-8804682956.80, -7.00) to (-8804682953.82, -4.03). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920742.141347725] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51 0.18) is out of map bounds (-8804682956.80, -7.00, 0.00) to (-8804682953.82, -4.03, 0.78). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920742.341178350] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[component_container_isolated-1] [WARN] [1702920742.341226145] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51) is out of map bounds (-8912057139.20, -7.00) to (-8912057136.22, -4.03). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920742.341333770] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51 0.18) is out of map bounds (-8912057139.20, -7.00, 0.00) to (-8912057136.22, -4.03, 0.78). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920742.541108057] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[component_container_isolated-1] [WARN] [1702920742.541148333] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51) is out of map bounds (-9019431321.60, -7.00) to (-9019431318.62, -4.03). The costmap cannot raytrace for it.
[component_container_isolated-1] [WARN] [1702920742.541244577] [local_costmap.local_costmap]: Sensor origin at (7263490040.02, -5.51 0.18) is out of map bounds (-9019431321.60, -7.00, 0.00) to (-9019431318.62, -4.03, 0.78). The costmap cannot raytrace for it.

Issue: No generated costmap
Reason: Wrong odom value

SOLUTION:
Change:
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};

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

Successfully merging this pull request may close these issues.

2 participants