//全局碰撞检查 //copied_state携带机器人信息,acm携带了环境的信息 collision_result.clear(); planning_scene.checkCollision(collision_request, collision_result, copied_state, acm); ROS_INFO_STREAM("Test 6: Current state is " << (collision_result.collision ? "in" : "not in") << " self collision");
//约束检查 //PlanningScene类也提供了方便进行约束检查的调用函数。 //约束一般分为两类,(1)运动学约束:比如说关节约束,位置约束,方向约束和能见度约束 (2)使用者通过回调声明的约束 //检查运动学约束 //We will first define a simple position and orientation constraint on the end-effector of the right_arm of the PR2 robot. std::string end_effector_name = joint_model_group->getLinkModelNames().back();
//定义the attached object消息 //我们将会使用这个消息从世界中加减物体,以及“attach the object to the robot” moveit_msgs::AttachedCollisionObject attached_object; attached_object.link_name = "r_wrist_roll_link"; /* The header must contain a valid TF frame*/ attached_object.object.header.frame_id = "r_wrist_roll_link"; /* The id of the object */ attached_object.object.id = "box";
/* A default pose */ geometry_msgs::Pose pose; pose.orientation.w = 1.0;//为何不定义x,y,z?
/* Define a box to be attached */ shape_msgs::SolidPrimitive primitive; primitive.type = primitive.BOX; primitive.dimensions.resize(3); primitive.dimensions[0] = 0.1; primitive.dimensions[1] = 0.1; primitive.dimensions[2] = 0.1;
//完成attach the objiect to the robot操作,opreation要制成ADD attached_object.object.operation = attached_object.object.ADD;
//把物体加入环境,之前的怎么算? ROS_INFO("Adding the object into the world at the location of the right wrist."); moveit_msgs::PlanningScene planning_scene; planning_scene.world.collision_objects.push_back(attached_object.object); planning_scene.is_diff = true; planning_scene_diff_publisher.publish(planning_scene); sleep_time.sleep();
//Attach an object to the robot //当机器人从环境中抓取物体时,我们需要“attach an object to the robot”,任何有关于机器人模型的操作都会考虑到这个物体
//Attach an object to the robot需要两部操作 //1.将物体从世界中移除 //2.将物体加入机器人模型
ROS_INFO("Attaching the object to the right wrist and removing it from the world."); planning_scene.world.collision_objects.clear();//首先确保这个话题不和其他的物体相关联 planning_scene.world.collision_objects.push_back(remove_object);//从世界移除物体 planning_scene.robot_state.attached_collision_objects.push_back(attached_object);//加入机器人 planning_scene_diff_publisher.publish(planning_scene);//发布出相应的消息
sleep_time.sleep();
//Detach an object from the robot //上述操作分为两步 //1.从机器人移除物体 //2.重新加回世界 moveit_msgs::AttachedCollisionObject detach_object; detach_object.object.id = "box"; detach_object.link_name = "r_wrist_roll_link"; detach_object.object.operation = attached_object.object.REMOVE;
ROS_INFO("Detaching the object from the robot and returning it to the world."); planning_scene.robot_state.attached_collision_objects.clear(); planning_scene.robot_state.attached_collision_objects.push_back(detach_object); planning_scene.world.collision_objects.clear(); planning_scene.world.collision_objects.push_back(attached_object.object); planning_scene_diff_publisher.publish(planning_scene);
sleep_time.sleep();//整体与之上是一致的
//将物体移除世界 ROS_INFO("Removing the object from the world."); planning_scene.robot_state.attached_collision_objects.clear(); planning_scene.world.collision_objects.clear(); planning_scene.world.collision_objects.push_back(remove_object); planning_scene_diff_publisher.publish(planning_scene);
//调用这个规划 context = planner_instance->getPlanningContext(planning_scene, req, res.error_code_); /* Call the Planner */ context->solve(res); /* Check that the planning was successful */ if(res.error_code_.val != res.error_code_.SUCCESS) { ROS_ERROR("Could not compute plan successfully"); return 0; } /* Visualize the trajectory */ ROS_INFO("Visualizing the trajectory"); res.getMessage(response); display_trajectory.trajectory_start = response.trajectory_start; display_trajectory.trajectory.push_back(response.trajectory);
/* Now you should see two planned trajectories in series*/ display_publisher.publish(display_trajectory);
/* We will add more goals. But first, set the state in the planning scene to the final state of the last plan */ robot_state.setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions);
/* Now, we go back to the first goal*/ req.goal_constraints.clear(); req.goal_constraints.push_back(pose_goal); context = planner_instance->getPlanningContext(planning_scene, req, res.error_code_); context->solve(res); res.getMessage(response);//标准方式 display_trajectory.trajectory.push_back(response.trajectory); display_publisher.publish(display_trajectory);
/* First, set the state in the planning scene to the final state of the last plan */ robot_state.setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); /* Now, let‘s try to move to this new pose goal*/ req.goal_constraints.clear(); req.goal_constraints.push_back(pose_goal_2);