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

Fixes for using generate-state_database #1412

Merged
merged 3 commits into from
Aug 9, 2022

Conversation

ejalaa12
Copy link
Contributor

@ejalaa12 ejalaa12 commented Jul 1, 2022

On galactic the generate_state_database script is not working.
This PR solves 3 issues that were blocking it from working properly.

Issue 1: planning_group parameter not declared

To reproduce simply run the generate_state_database node as follows

ros2 run moveit_planners_ompl generate_state_database --ros-args -p planning_group:=mygroup

The error you get is

[FATAL] [1656670955.089432190] [moveit.planners_ompl.generate_state_database]: ~planning_group parameter has to be specified.

This happens because none of the parameters that this node uses are declared before the get_parameter method is called.
The first commit simply adds the automatically_declare_paramters_from_override(true) to the node option.
This should be fine for such an isolated script.

Issue 2: planning constraints parameters are not found

Once the previous issue is fixed, you get the following error, even with the parameters passed correctly.

ros2 run moveit_planners_ompl generate_state_database --ros-args --params-file constraints.yaml 
[ERROR] [1656671355.887499755] [moveit_kinematic_constraints.utils]: constraint parameter does not specify its type
[FATAL] [1656671355.887591347] [moveit.planners_ompl.generate_state_database]: Could not find valid constraint description in parameter '/generate_state_database.constraints'. Please upload correct correct constraint description or remap the parameter.

The params file being:

generate_state_database:
  ros__parameters:
    planning_group: mygroup
    use_current_scene: false
    constraints:
      name: some_constraints
      constraint_ids: [constraint_2]
      constraints:
        constraint_2:
          type: joint
          frame_id: base_link
          joint_name: jr_link3_robot
          position: 0.0
          tolerance: 0.3
          weight: 1.0

This is because the constraints parameters are not looked up correctly. The second commit fixes that.
However I'm not 100% sure about what format what expected by the constraint loader. After my fix, the above param file now works.

Issue 3: Failed to serialize message when writing the database file

Once issue2 is fixed, we get the following error:

[INFO] [1656677299.939890208] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00282835 seconds
[INFO] [1656677299.940199400] [moveit_robot_model.robot_model]: Loading robot model 'robot'...
[WARN] [1656677299.940807662] [moveit_robot_model.robot_model]: Link base_link has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[WARN] [1656677299.941647022] [moveit_robot_model.robot_model]: Link link1 has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[WARN] [1656677299.943386970] [moveit_robot_model.robot_model]: Link link2 has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[WARN] [1656677299.943607031] [moveit_robot_model.robot_model]: Link link3 has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[WARN] [1656677299.949846154] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
[INFO] [1656677299.967788637] [moveit_planning_interface.planning_interface]: The timeout for planning must be positive (0.000000 specified). Assuming one second instead.
[WARN] [1656677299.967832315] [moveit.ompl_planning.model_based_planning_context]: It looks like the planning volume was not specified.
Debug:   Starting goal sampling thread
Debug:   Waiting for space information to be set up before the sampling thread can begin computation...
[INFO] [1656677299.969216385] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'robot' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
Debug:   robot/robot: Planner range detected to be 121.256637
[INFO] [1656677299.969750299] [moveit.planners_ompl.generate_state_database]: Generating Joint Space Constraint Approximation Database for constraint:
some_constraints
Debug:   Attempting to stop goal sampling thread...
Warning: Goal sampling thread never did any work.
         at line 129 in /tmp/binarydeb/ros-galactic-ompl-1.5.2/src/ompl/base/goals/src/GoalLazySamples.cpp
Debug:   Stopped goal sampling thread after 0 sampling attempts
[INFO] [1656677299.980057213] [moveit.ompl_planning.constraints_library]: Generated 0 states in 0.000005 seconds
[INFO] [1656677299.980093963] [moveit.ompl_planning.constraints_library]: Constrained sampling rate: 0.000000
[ERROR] [1656677299.980100348] [moveit.ompl_planning.constraints_library]: No StateStoragePtr found - implement better solution here.
[INFO] [1656677299.980183606] [moveit.ompl_planning.constraints_library]: Spent 0.000632 seconds constructing the database
[INFO] [1656677299.980375629] [moveit.ompl_planning.constraints_library]: Saving 1 constrained space approximations to 'constraint_approximation_database'
[ERROR] [1656677299.984306434] [moveit.ompl_planning.constraints_library]: Failed to serialize message!
Debug:   Serializing 0 states
[INFO] [1656677299.984615310] [moveit.planners_ompl.generate_state_database]: Successfully generated Joint Space Constraint Approximation Database for constraint:
some_constraints
[INFO] [1656677299.984625655] [moveit.planners_ompl.generate_state_database]: The database has been saved in your local folder 'constraint_approximation_database'

This is because the rmw_serialized_message_t is not instantiated correctly (see here).
Third commit fixes it.

@mergify
Copy link

mergify bot commented Jul 1, 2022

Please target the main branch for development, we will backport the changes to galactic for you if approved and if they don't break API.

@ejalaa12 ejalaa12 changed the base branch from galactic to main July 1, 2022 12:41
@mergify
Copy link

mergify bot commented Jul 1, 2022

This pull request is in conflict. Could you fix it @ejalaa12?

@ejalaa12 ejalaa12 force-pushed the bug-generate-state-database branch from de7ab12 to c04f9ac Compare July 1, 2022 12:43
@ejalaa12 ejalaa12 marked this pull request as ready for review July 1, 2022 12:48
@codecov
Copy link

codecov bot commented Jul 1, 2022

Codecov Report

Merging #1412 (cf714d5) into main (0b5a7fa) will increase coverage by 0.01%.
The diff coverage is 0.00%.

@@            Coverage Diff             @@
##             main    #1412      +/-   ##
==========================================
+ Coverage   50.99%   51.00%   +0.01%     
==========================================
  Files         380      380              
  Lines       31743    31744       +1     
==========================================
+ Hits        16184    16187       +3     
+ Misses      15559    15557       -2     
Impacted Files Coverage Δ
moveit_core/kinematic_constraints/src/utils.cpp 24.53% <0.00%> (ø)
.../ompl_interface/src/detail/constraints_library.cpp 0.00% <0.00%> (ø)
moveit_core/robot_state/src/robot_state.cpp 47.37% <0.00%> (-0.07%) ⬇️
...nning_scene_monitor/src/planning_scene_monitor.cpp 45.73% <0.00%> (+0.44%) ⬆️

Help us with your feedback. Take ten seconds to tell us how you rate us. Have a feature suggestion? Share it here.

Copy link
Member

@henningkayser henningkayser left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ejalaa12 thanks a lot for your fixes. Could you run pre-commit to fix formatting and ideally rebase the three fixes as three individual commits on main?

@@ -537,7 +537,7 @@ bool constructConstraints(const rclcpp::Node::SharedPtr& node, const std::string
return false;

for (auto& constraint_id : constraint_ids)
constraint_id.insert(0, constraints_param);
constraint_id.insert(0, constraints_param + ".");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you add "." here, wouldn't it be redundant in line 488 etc?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

constraint_param is passed as parameter to the function, and its value is constraints (see here and here)


The purpose of this for-loop is to prefix the contraint_id with the correct param "namespace".
Assuming that before the for-loop,

constraint_ids = ["contraintA", "constraintB"];

After the loop, and without the fix, it becomes:

contraint_ids =  ["contraintscontraintA", "contraintsconstraintB"];

Instead of (with the fix)

contraint_ids =  ["contraints.contraintA", "contraints.constraintB"];

Line 488, also prefix (again) those constraint_ids, without the second fix, it becomes

contraint_ids =  [".constraints.contraints.contraintA", ".constraints.contraints.constraintB"];

where the first . is not necessary, that's why I removed it.


I find the second prefixing (inside collectConstraints) confusing anyway. I guess it all boils down to how should the yaml file be structured.
Do you guys have an example for this file ?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

To continue on my last remark, we could have the yaml look like this:

generate_state_database:
  ros__parameters:
    planning_group: mygroup
    use_current_scene: false
    constraints:
      name: some_constraints
      constraint_ids: [constraintA]
      constraintA:
        type: joint
        frame_id: base_link
        joint_name: jr_link3_robot
        position: 0.0
        tolerance: 0.3
        weight: 1.0

In which case, the for-loop in the constructConstraints method would look like this:

  for (auto& constraint_id : constraint_ids)
    constraint_id.insert(0, constraints_param + ".");

and inside the collectConstraint method we change line 479 to

const auto constraint_param = constraint_id;

instead of const auto constraint_param = ".constraints." + constraint_id

@henningkayser henningkayser added backport-humble Mergify label that triggers a PR backport to Humble backport-galactic Mergify label that triggers a PR backport to Galactic backport-foxy Mergify label that triggers a PR backport to Foxy labels Aug 5, 2022
@ejalaa12 ejalaa12 force-pushed the bug-generate-state-database branch from f7e859e to cf714d5 Compare August 8, 2022 09:54
@ejalaa12
Copy link
Contributor Author

ejalaa12 commented Aug 8, 2022

Hey @henningkayser, thanks for the review.

I've rebased my changes onto main, and squashed them to have one commit per fix.
I've also run the pre-commit and fixed the syntax.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
backport-foxy Mergify label that triggers a PR backport to Foxy backport-galactic Mergify label that triggers a PR backport to Galactic backport-humble Mergify label that triggers a PR backport to Humble
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants