本篇文章介绍MoveIt!在实际开发中需要注意的一些潜规则,官方文档未提到但在实际工作中有用的一些技能。
一、圆弧轨迹规划
上一篇中介绍了直线插补,将waypoints用直线连接,而圆弧轨迹插补API是未提供的,实际中比如焊接是需要这样的轨迹的,我们自己需要实现。方法是用很多直线段模拟圆弧,取点越多越接近实际圆弧:
圆弧生成
直接看代码:
#include
#include
#include
#include
using namespace std;
int main(int argc, char **argv)
{
ros::init(argc, argv, "move_with_circle");
ros::AsyncSpinner spinner(1);
spinner.start();
moveit::planning_interface::MoveGroupInterface ur5("manipulator");
string eef_link = ur5.getEndEffector();
std::string reference_frame = "base_link";
ur5.setPoseReferenceFrame(reference_frame);
ur5.allowReplanning(true);
ur5.setGoalPositionTolerance(0.001);
ur5.setGoalOrientationTolerance(0.01);
ur5.setMaxAccelerationScalingFactor(0.8);
ur5.setMaxVelocityScalingFactor(0.8);
// 控制机械臂先回到初始化位置
ur5.setNamedTarget("home");
ur5.move();
sleep(1);
geometry_msgs::Pose target_pose;
target_pose.orientation.x = 0.70711;
target_pose.orientation.y = 0;
target_pose.orientation.z = 0;
target_pose.orientation.w = 0.70711;
target_pose.position.x = 0.070859;
target_pose.position.y = 0.36739;
target_pose.position.z = 0.84716;
ur5.setPoseTarget(target_pose);
ur5.move();
vector<:pose> waypoints;
waypoints.push_back(target_pose);
//在xy平面内生成一个圆周
double centerA = target_pose.position.x;
double centerB = target_pose.position.y;
double radius = 0.15;
for(double theta = 0.0; theta < M_PI*2; theta += 0.