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

AsyncSpinner and MoveIt!

asked 2019-10-02 04:47:54 -0500

A_YIng gravatar image

Hello, When I followed the tutorials of MoveIt!(C++), I found this line:

  ros::AsyncSpinner spinner(1); 
  spinner.start();

I searched for it and know its definition, but my question is why moveit needs asyncspinner to run the program? If delete it, the error is occurred.

The whole code is below:

  ros::init(argc, argv, "move_to_position");
  ros::NodeHandle nh;

  ros::AsyncSpinner spinner(1); 
  spinner.start();

  moveit::planning_interface::MoveGroupInterface group_r1("r1");

  group_r1.setGoalJointTolerance(0.001);
  group_r1.setMaxAccelerationScalingFactor(0.5);
  group_r1.setMaxVelocityScalingFactor(0.03);

  geometry_msgs::PoseStamped object_pose;

    group_r1.setStartState(*group_r1.getCurrentState());
    group_r1.setPoseTarget(pose);

    moveit::planning_interface::MoveGroupInterface::Plan group_Planer;

    bool success = (group_r1.plan(group_Planer) == moveit::planning_interface::MoveItErrorCode::SUCCESS);

    if (success)
    {
      ros::Duration(1).sleep();
      group_r1.execute(group_Planer);
    }

Thanks for your answer!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-10-02 07:14:10 -0500

lucascoelho gravatar image

While ros::spin() blocks the current thread, AsyncSpinner creates a thread with a spinner, so you can continue using the current thread. On the example code provided above, it creates one spinner thread and starts it in parallel with your main thread. If you want to know more about ros::spin and AsyncSpinner, I recommend reading this blog post: https://yuzhangbit.github.io/tools/se...

edit flag offensive delete link more

Comments

I still confuse about it. Why can't it just use the current thread(main thread) to run the moveit program?

A_YIng gravatar image A_YIng  ( 2019-10-02 07:19:58 -0500 )edit

I think it's just a design choice, there are other ways to make the program above to work with only the current thread. I'm not very sure, but I think if you add a ros::spinOnce() inside the if (success) bracket, it would work as well. But you definitely need some kind of spinner either ros::spin(), ros::spinOnce, AsyncSpinner or MultiThreadedSpinner to process the ROS messages and callbacks

lucascoelho gravatar image lucascoelho  ( 2019-10-02 07:57:45 -0500 )edit

Thanks, I will give a try. Now, it's more clearer to me.

A_YIng gravatar image A_YIng  ( 2019-10-02 22:23:50 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-10-02 04:47:54 -0500

Seen: 705 times

Last updated: Oct 02 '19