1 添加Planning Scene Interface头文件
#include <moveit/planning_scene_interface/planning_scene_interface.h>
2 改变目标位姿
// Set a target Pose
auto const target_pose = [] {
geometry_msgs::msg::Pose msg;
msg.orientation.w = 1.0;
msg.position.x = 0.28;
msg.position.y = 0.4; // <---- This value was changed
msg.position.z = 0.5;
return msg;
}();
move_group_interface.setPoseTarget(target_pose);
3 创建一个碰撞物体
在下一个代码块中,我们创建了一个碰撞物体。
第一个需要注意的是,物体被放置在机器人坐标系下。如果我们有一个感知系统,能够报告场景中障碍物的位置,这就是该系统将要建立的一类信息。在本例子中我们手动来创建它。
另外要注意代码块的结尾处,我们设置该信息的操作为ADD
,这样能够允许在后面的操作中将物体添加到碰撞场景。
把此代码块插入到【设置目标位姿】和【创建规划】之间。
// 创建用于避障的碰撞对象
auto const collision_object = [frame_id =
move_group_interface.getPlannin