You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
When working around #2219 by merging use_sim_time:=True into the MoveIt config dictionary, I'm seeing mixed results:
use_sim_time is actually set to True 🎉
The moveit_py node is crashing due to an rclcpp::exceptions::InvalidParameterValueException
In particular it prints:
[motion_planning_python_api_tutorial.py-2] terminate called after throwing an instance of 'rclcpp::exceptions::InvalidParameterValueException'
[motion_planning_python_api_tutorial.py-2] what(): parameter 'qos_overrides./clock.subscription.durability' could not be set:
A quick search brought me to this issue comment, pointing out that use_sim_time:=True will enable qos_override callbacks on the /clock topic. Question is, why does everything work with the C++ versions MoveGroup/MoveItCpp, and why do we run into this exception with moveit_py?
I have briefly skimmed the node initialization and didn't find any obvious issues.
For context, I've been working on a MoveIt+Gazebo setup and wanted to add a MoveItPy example. Here are instructions for running different launch files in a docker compose container. You'll find that all service targets besides python_gazebo work, python_gazebo fails for the described reason.
Do things actually work with MoveItCpp? Like if we launch the MoveItCpp tutorial and similarly test with use_sim_time as in these 2 issues, are the errors the same or not?
And if they aren't, the only difference I see in the tutorial vs. MoveItPy is the addition of allow_undeclared_parameters(true) ... which I don't know if it will do much?
EDIT: I tested the MoveItCpp tutorial and it still works with use_sim_time: True and allow_undeclared_parameters...
@sea-bass thanks for testing.. Yes, MoveGroup works and MoveItCpp should work as well since that's being used internally. The allow_undeclared_parameters(true) flag is also used by MoveGroup here, so that shouldn't be the issue.
My current guess is that MoveItPy is missing some ROS args for the global context (whatever that really means...)
Description
When working around #2219 by merging
use_sim_time:=True
into the MoveIt config dictionary, I'm seeing mixed results:use_sim_time
is actually set toTrue
🎉rclcpp::exceptions::InvalidParameterValueException
In particular it prints:
A quick search brought me to this issue comment, pointing out that
use_sim_time:=True
will enable qos_override callbacks on the/clock
topic. Question is, why does everything work with the C++ versions MoveGroup/MoveItCpp, and why do we run into this exception with moveit_py?I have briefly skimmed the node initialization and didn't find any obvious issues.
For context, I've been working on a MoveIt+Gazebo setup and wanted to add a MoveItPy example.
Here are instructions for running different launch files in a docker compose container. You'll find that all service targets besides python_gazebo work, python_gazebo fails for the described reason.
Your environment
Steps to reproduce
Try passing
use_sim_time:=True
like this.Expected behaviour
The launch file should work and allow using sim time with moveit_py.
Actual behaviour
The Exception is thrown, node dies.
The text was updated successfully, but these errors were encountered: