MoveIt!自定义低自由度机械臂遇逆运动学求解失败问题

本人在一个机械臂项目中建模了一个四自由度机械臂,成功导入MoveIt后,机械臂可以通过api或RViz GUI进行关节空间规划(指定机械臂构型)。因为四自由度机械臂末端规划几乎无法同时指定姿态和位置,所以选用set_position_target()函数指定了end_effector的位置,进行单点规划。规划的具体语句(其中group是commander类,用法见MoveGroupCommander类):

group.set_position_target([-1.515159, 1.970219, 0.501001], 'link4')
success = group.go(wait=True)
group.stop()
group.clear_pose_targets()

但是还是没能找到逆运动学解,moveit终端报错:

 arm_nc/arm_nc: Unable to sample any valid states for goal tree
 arm_nc/arm_nc: Created 1 states (1 start + 0 goal)
 No solution found after 5.009792 seconds

规划节点终端报错规划超时:[ INFO] [1685523788.560167099]: ABORTED: TIMED_OUT

翻了社区后,有一个有代表性的帖子:https://answers.ros.org/question/322366/moveit-unable-to-sample-any-valid-states-for-goal-tree/

总结有两个解决办法:

1、(用set_pose_target)orientation和position的精度要给到%.6f级,如pose.orientation.w=1.000000。

2、增大tolerance,通过set_position_tolerance()和set_orientation_tolerance()完成。

但这两种方法在我这都不work,最后尝试解决了,于是增加第三种解决办法,前两种不行的朋友可以试试:

在moveit规划包内的config文件夹内,修改Kinematics.yaml文件,在后面加入:

position_only_ik: True

指定逆运动学只考虑位置约束,不考虑姿态约束,加入后规划成功。这说明,即使官方文档中set_position_target()的注释为:

“Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.”

在plan过程中还是存在姿态约束。

总结:

低自由度的机械臂用moveit实现轨迹规划时,可以考虑将position_only_ik打开,以保证输入的点都有近似的逆运动学解。

  • 5
    点赞
  • 25
    收藏
    觉得还不错? 一键收藏
  • 7
    评论
7自由度机械臂逆运动学解析解非常复杂,需要用到复杂的数学方法和算法,但是可以通过一些库和工具来简化解决过程。 以下是一个使用 ROS 中的 MoveIt! 库解决 7 自由度机械臂逆运动学的示例代码: ```c++ #include <ros/ros.h> #include <moveit/move_group_interface/move_group_interface.h> #include <moveit/planning_scene_interface/planning_scene_interface.h> #include <moveit_msgs/DisplayTrajectory.h> #include <moveit_msgs/RobotTrajectory.h> #include <moveit_msgs/RobotState.h> #include <moveit_msgs/Constraints.h> #include <moveit_msgs/JointConstraint.h> #include <moveit_msgs/MoveGroupActionResult.h> #include <moveit_msgs/PlanningScene.h> #include <moveit/kinematics_plugin_loader/kinematics_plugin_loader.h> #include <moveit/robot_state/conversions.h> #include <moveit/robot_trajectory/robot_trajectory.h> int main(int argc, char** argv) { ros::init(argc, argv, "moveit_ik_demo"); ros::NodeHandle node_handle; ros::AsyncSpinner spinner(1); spinner.start(); static const std::string PLANNING_GROUP = "arm"; moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP); moveit::planning_interface::PlanningSceneInterface planning_scene_interface; const robot_state::JointModelGroup* joint_model_group = move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP); // 设置目标位置 geometry_msgs::Pose target_pose; target_pose.orientation.w = 1.0; target_pose.position.x = 0.4; target_pose.position.y = -0.2; target_pose.position.z = 0.4; move_group.setPoseTarget(target_pose); // 执行规划和移动 moveit::planning_interface::MoveGroupInterface::Plan my_plan; bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS); ROS_INFO("Visualizing plan 1 (pose goal) %s", success ? "" : "FAILED"); move_group.move(); ros::shutdown(); return 0; } ``` 该示例代码中,首先设置了机械臂规划组和目标位置,然后调用 MoveIt! 库中的 `plan()` 方法进行运动规划,最后调用 `move()` 方法执行运动。这样,就可以实现机械臂的自动逆运动学解析解。
评论 7
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值