AsyncSpinner and MoveIt!
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!