roslaunch marm_planning arm_planning_with_trail.launch
rosrun marm_planning moveit_cartesian_demo.py _cartesian:=True
注意笛卡尔launch文件已经不同,对比如下。
arm_planning_with_trail.launch
<launch>
<!-- 不使用仿真时间 -->
<param name="/use_sim_time" value="false" />
<!-- 启动 arbotix driver-->
<arg name="sim" default="true" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find marm_description)/urdf/arm.xacro'" />
<node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen">
<rosparam file="$(find marm_description)/config/arm.yaml" command="load" />
<param name="sim" value="true"/>
</node>
<node name="gripper_controller" pkg="arbotix_controllers" type="gripper_controller">
<rosparam>
model: singlesided
invert: false
center: 0.0
pad_width: 0.004
finger_length: 0.08
min_opening: 0.0
max_opening: 0.06
joint: finger_joint1
</rosparam>
</node>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="rob_st_pub" />
<include file="$(find marm_moveit_config)/launch/move_group.launch" />
<!-- 启动rviz可视化界面 -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find marm_planning)/config/arm_paths.rviz" required="true" />
</launch>
arm_planning.launch
<launch>
<!-- 不使用仿真时间 -->
<param name="/use_sim_time" value="false" />
<!-- 启动 arbotix driver-->
<arg name="sim" default="true" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find marm_description)/urdf/arm.xacro'" />
<node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen">
<rosparam file="$(find marm_description)/config/arm.yaml" command="load" />
<param name="sim" value="true"/>
</node>
<node name="gripper_controller" pkg="arbotix_controllers" type="gripper_controller">
<rosparam>
model: singlesided
invert: false
center: 0.0
pad_width: 0.004
finger_length: 0.08
min_opening: 0.0
max_opening: 0.06
joint: finger_joint1
</rosparam>
</node>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="rob_st_pub" />
<include file="$(find marm_moveit_config)/launch/move_group.launch" />
<!-- 启动rviz可视化界面 -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find marm_planning)/config/pick_and_place.rviz" required="true" />
</launch>
区别是rviz文件的差距!现在不知道是官网给的还是自己编写,未知数,全学完解决。
运行效果如下。
其中python脚本,moveit_cartesian_demo.py
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, sys
import moveit_commander
from moveit_commander import MoveGroupCommander
from geometry_msgs.msg import Pose
from copy import deepcopy
class MoveItCartesianDemo:
def __init__(self):
# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)
# 初始化ROS节点
rospy.init_node('moveit_cartesian_demo', anonymous=True)
# 是否需要使用笛卡尔空间的运动规划
cartesian = rospy.get_param('~cartesian', True)
# 初始化需要使用move group控制的机械臂中的arm group
arm = MoveGroupCommander('arm')
# 当运动规划失败后,允许重新规划
arm.allow_replanning(True)
# 设置目标位置所使用的参考坐标系
arm.set_pose_reference_frame('base_link')
# 设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.set_goal_position_tolerance(0.01)
arm.set_goal_orientation_tolerance(0.1)
# 获取终端link的名称
end_effector_link = arm.get_end_effector_link()
# 控制机械臂运动到之前设置的“forward”姿态
arm.set_named_target('forward')
arm.go()
# 获取当前位姿数据最为机械臂运动的起始位姿
start_pose = arm.get_current_pose(end_effector_link).pose
# 初始化路点列表
waypoints = []
# 将初始位姿加入路点列表
if cartesian:
waypoints.append(start_pose)
# 设置第二个路点数据,并加入路点列表
# 第二个路点需要向后运动0.2米,向右运动0.2米
wpose = deepcopy(start_pose)
wpose.position.x -= 0.2
wpose.position.y -= 0.2
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
# 设置第三个路点数据,并加入路点列表
wpose.position.x += 0.05
wpose.position.y += 0.15
wpose.position.z -= 0.15
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
# 设置第四个路点数据,回到初始位置,并加入路点列表
if cartesian:
waypoints.append(deepcopy(start_pose))
else:
arm.set_pose_target(start_pose)
arm.go()
rospy.sleep(1)
if cartesian:
fraction = 0.0 #路径规划覆盖率
maxtries = 100 #最大尝试规划次数
attempts = 0 #已经尝试规划次数
# 设置机器臂当前的状态作为运动初始状态
arm.set_start_state_to_current_state()
# 尝试规划一条笛卡尔空间下的路径,依次通过所有路点
while fraction < 1.0 and attempts < maxtries:
(plan, fraction) = arm.compute_cartesian_path (
waypoints, # waypoint poses,路点列表
0.01, # eef_step,终端步进值
0.0, # jump_threshold,跳跃阈值
True) # avoid_collisions,避障规划
# 尝试次数累加
attempts += 1
# 打印运动规划进程
if attempts % 10 == 0:
rospy.loginfo("Still trying after " + str(attempts) + " attempts...")
# 如果路径规划成功(覆盖率100%),则开始控制机械臂运动
if fraction == 1.0:
rospy.loginfo("Path computed successfully. Moving the arm.")
arm.execute(plan)
rospy.loginfo("Path execution complete.")
# 如果路径规划失败,则打印失败信息
else:
rospy.loginfo("Path planning failed with only " + str(fraction) + " success after " + str(maxtries) + " attempts.")
# 控制机械臂回到初始化位置
arm.set_named_target('home')
arm.go()
rospy.sleep(1)
# 关闭并退出moveit
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
try:
MoveItCartesianDemo()
except rospy.ROSInterruptException:
pass
版权声明:本文为wzfafabga原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明。