Git Product home page Git Product logo

Comments (4)

SteveMacenski avatar SteveMacenski commented on August 30, 2024 1

The polygons are all published on the process rate:

- which you should be able to see in your terminal while echoing the topic a stream of data. This again uses system default QoS so some of this might be your own issue of introducing transient local into the mix.

I just tested and see no issues, I would again however point to making sure that your cmd_vel is actually configured to get to the collision monitor since you mentioned changing some of those settings. Process is only called on the cmd_vel trigger which would explain all of this behavior, since we also publish the polygon at the start with activate, but just a single time.

So you'd see only the single polygon from the initial state and not updated. It gets updated by a re-subscribe since its in the base_footprint frame, so when it gets the new data, rviz automatically converts it into your visualizer's fixed frame.

If you echo and it appears once and not a live stream, it means the collision monitor itself is not receiving command velocity data and you should review the configuration guide or main examples for setting up the collision monitor: https://docs.nav2.org/configuration/packages/configuring-collision-monitor.html

I did mention that above in:

Your remark below would make me want to ensure that you have properly remapped that topic for the the collision monitor as well, since obviously the collision monitor needs to obtain the cmd-vel to do useful work.

Please review that.

from navigation2.

SteveMacenski avatar SteveMacenski commented on August 30, 2024

It looks like your QoS settings are wrong on that display?

rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS(); // set to default
polygon_pub_ = node->create_publisher<geometry_msgs::msg::PolygonStamped>(
polygon_pub_topic, polygon_qos);
that could be contributing I suppose, though I don't have an immediately deep answer as to 'why' it would appear once in that case.

Is it working properly minus the visualization? Just making sure I shouldn't scrutinize the code or your configuration for possible issues and its just a transport on the visualizations. Your remark below would make me want to ensure that you have properly remapped that topic for the the collision monitor as well, since obviously the collision monitor needs to obtain the cmd-vel to do useful work.

Change the remapping topics of controller_server and nav2_smoother from cmd_vel_nav to cmd_vel_raw.

from navigation2.

marcusvinicius178 avatar marcusvinicius178 commented on August 30, 2024

Hi Steve thanks for your attention on this question.

I'm encountering an issue with visualizing polygons using the default QoS settings.

When I launch the collision monitor node first, the polygons always appear without issues, provided I set the Durability QoS to transient_local. This setting ensures that the data is retained and available to late-joining subscribers. Here's a screenshot of the working setup:

polygon_stop

There is one **interesting detail ** that I have noticed: If I launch the collision monitor node first then the polygons always appear with no issues, (although must be mandatory to set the Durability QoS to transient_local).

When I set both to transient_local it works:
image

However, if I launch the simulation first and then the collision monitor node, the behavior becomes unstable. The polygons do not always appear; sometimes only polygon_stop appears, and other times neither of them show up. Despite this, the messages seem to be sent correctly, as echoed in the terminal, but they are not visualized properly:

image

Chuck commented on my issue on robotics stack exchange

"When I followed the link to the tutorial you were using, I saw this statement: Both polygon shapes in the tutorial were set statically. However, there is an ability to dynamically adjust them over time using topic messages containing vertices points for polygons or footprints. For more information, please refer to the configuration guide. which sounds to me like it exactly describes what you're seeing - you get a single static polygon that does not adjust over time. Have you tried testing with dynamic polygons?"

I believe this is the last behavior I need to fix. I want the polygons to dynamically follow my robot's base_footprint. Unfortunately, I did not understand how to set the parameters and launch file for dynamic behavior from the documentation how to set the parameters and launch file to get the dynamic behavior (In Alexey tutorial video I have not checked any additional steps required to set on configuration file). Could you help me configure this to achieve dynamic polygon behavior?

from navigation2.

marcusvinicius178 avatar marcusvinicius178 commented on August 30, 2024

Thanks Steve!

You were correct the issue relied on using the cmd_vel_raw instead cmd_vel_nav in navigation.launch because I was following the Alexey tutorial but without following the context...

So you'd see only the single polygon from the initial state, which was not updated. It gets updated by a re-subscribe since its in the base_footprint frame, so when it gets the new data, rviz automatically converts it into your visualizer's fixed frame.

This subscription relation to cmd_vel also explains why the polygon boxes appear on rviz2 after the robot starts moving!

If you echo and it appears once and not a live stream, it means the collision monitor itself is not receiving command velocity data and you should review the configuration guide or main examples for setting up the collision monitor: https://docs.nav2.org/configuration/packages/configuring-collision-monitor.html

Finally the data flow is dynamic: https://youtu.be/vnL7_CqBup8

from navigation2.

Related Issues (20)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.