ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
6

MoveIt! move_group plan function not returning [closed]

asked 2013-10-16 05:15:03 -0500

I can't figure out what I am doing wrong that would cause this issue. I originally was just using the move() function but that wasn't returning either. I thought it had something to do with just running this in rviz and not really executing anything.

So I switched to plan() instead but found I was having the same issue. I've attached the barebones I've boiled this down to:

#include <ros/ros.h>
#include <moveit/move_group_interface/move_group.h>

int main(int argc, char **argv) {
    ros::init(argc, argv, "move_group_interface_demo");
    ros::NodeHandle node;

    move_group_interface::MoveGroup group("arm");

    ros::Rate rate(1);
    while (node.ok()){
        group.setRandomTarget();

        moveit::planning_interface::MoveGroup::Plan  plan;

        ROS_INFO("Planning");

        if(group.plan(plan)) {
            ROS_INFO("Planning Successful");
        }
        else {
            ROS_WARN("Planning failed!");
        }
        rate.sleep();
    }

    ROS_INFO("DONE");

    ros::waitForShutdown();
    return 0;
}

Like I said, I'm sure it's a careless mistake that I'm not seeing. I'm using the demo.launch file created using the MoveIt! Setup Assistant. I see the plan being visualized in RViz after the planning is initiated? But the function doesn't return in this simple node.

In the terminal I see "Planning" being printed but neither the successful or failure messages print after that.

Also, I can use the planners in MoveIt! just fine inside of RViz to "plan and execute".

Any ideas?

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by skiesel
close date 2013-10-17 02:45:31

Comments

Perfect question! You'd better ask this at https://groups.google.com/forum/#!forum/moveit-users, and I'm sure you'll get a quick answer there.

Martin Günther gravatar image Martin Günther  ( 2013-10-17 01:52:24 -0500 )edit

Thanks Martin, I'll repost this to their google-group.

skiesel gravatar image skiesel  ( 2013-10-17 02:25:04 -0500 )edit

Thanks for the question (and the answer) skiesel. Was useful. :)

Damon gravatar image Damon  ( 2015-06-24 02:38:34 -0500 )edit

1 Answer

Sort by » oldest newest most voted
10

answered 2013-10-17 02:45:10 -0500

After a goodnight's sleep it hit me. THREADS. Ugh.

http://wiki.ros.org/roscpp/Overview/Callbacks%20and%20Spinning#Multi-threaded_Spinning

ros::AsyncSpinner spinner(1);
spinner.start();
edit flag offensive delete link more

Comments

Thanks! it works

ravipr009 gravatar image ravipr009  ( 2018-12-24 05:09:52 -0500 )edit

I had this issue in an Rviz panel which cannot own an AsyncSpinner, but the answer was also THREADS. The Moveit MotionPlanning plugin has good examples on how to launch threads with boost::bind.

fvd gravatar image fvd  ( 2020-09-09 03:14:31 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-10-16 05:15:03 -0500

Seen: 1,546 times

Last updated: Oct 17 '13