1、书接上文,首先需要把moveit_rviz.launch文件改回来,因为在这里暂时不需要进行gazebo仿真
moveit_rviz.launch
2、创建工作空间aubo_demo,依赖包为roscpp rospy std_msgs
好了到这里就可以开始愉快地编程了!(以下代码参考古月居)
正向运动学规划,就是直接设置每个joint的位置 python
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, sys
import moveit_commander
class MoveItFkDemo:
def __init__(self):
# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)
# 初始化ROS节点
rospy.init_node('moveit_fk_demo', anonymous=True)
# 初始化需要使用move group控制的机械臂中的arm group
arm = moveit_commander.MoveGroupCommander('manipulator')
# 设置机械臂运动的允许误差值
arm.set_goal_joint_tolerance(0.001)
# 设置允许的最大速度和加速度
arm.set_max_acceleration_scaling_factor(0.5)
arm.set_max_velocity_scaling_factor(0.5)
# 控制机械臂先回到初始化位置
arm.set_named_target('home')
arm.go() #规划和执行回到"home"点
rospy.sleep(1)
# 设置机械臂的目标位置,使用六轴的位置数据进行描述(单位:弧度)
# joint_positions = [0.391410, -0.676384, -0.376217, 0.0, 1.052834, 0.454125]
joint_positions = [1, -0.676384, -0.376217, 0.0, 1.052834, 0.454125]
arm.set_joint_value_target(joint_positions)
# 控制机械臂完成运动
arm.go()
rospy.sleep(1)
# 控制机械臂先回到初始化位置
arm.set_named_target('home')
arm.go()
rospy.sleep(1)
# 关闭并退出moveit
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
try:
MoveItFkDemo()
except rospy.ROSInterruptException:
pass
#include
#include
int main(int argc, char **argv) {
ros::init(argc, argv, "moveit_fk_demo");
ros::AsyncSpinner spinner(1);
spinner.start();
moveit::planning_interface::MoveGroupInterface arm("manipulator");
arm.setGoalJointTolerance(0.001);
arm.setMaxAccelerationScalingFactor(0.2);
arm.setMaxVelocityScalingFactor(0.2);
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
double targetPose[6] = {0.391410, -0.676384, -0.376217, 0.0, 1.052834, 0.454125};
std::vector joint_group_positions(6);
joint_group_positions[0] = targetPose[0];
joint_group_positions[1] = targetPose[1];
joint_group_positions[2] = targetPose[2];
joint_group_positions[3] = targetPose[3];
joint_group_positions[4] = targetPose[4];
joint_group_positions[5] = targetPose[5];
arm.setJointValueTarget(joint_group_positions);
arm.move();
sleep(1);
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
ros::shutdown();
return 0; }
逆向运动学规划,就是只设置机械臂顶端的终点位置
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, sys
import moveit_commander
from geometry_msgs.msg import PoseStamped, Pose
class MoveItIkDemo:
def __init__(self):
# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)
# 初始化ROS节点
rospy.init_node('moveit_ik_demo')
# 初始化需要使用move group控制的机械臂中的arm group
arm = moveit_commander.MoveGroupCommander('manipulator')
# 获取终端link的名称
end_effector_link = arm.get_end_effector_link()
# 设置目标位置所使用的参考坐标系
reference_frame = 'base_link'
arm.set_pose_reference_frame(reference_frame)
# 当运动规划失败后,允许重新规划
arm.allow_replanning(True)
# 设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.set_goal_position_tolerance(0.001)
arm.set_goal_orientation_tolerance(0.01)
# 设置允许的最大速度和加速度
arm.set_max_acceleration_scaling_factor(0.5)
arm.set_max_velocity_scaling_factor(0.5)
# 控制机械臂先回到初始化位置
arm.set_named_target('home')
arm.go()
rospy.sleep(1)
# 设置机械臂工作空间中的目标位姿,位置使用x、y、z坐标描述,
# 姿态使用四元数描述,基于base_link坐标系
target_pose = PoseStamped()
target_pose.header.frame_id = reference_frame
target_pose.header.stamp = rospy.Time.now()
target_pose.pose.position.x = 0.2593
target_pose.pose.position.y = 0.0636
target_pose.pose.position.z = 0.1787
target_pose.pose.orientation.x = 0.70692
target_pose.pose.orientation.y = 0.0
target_pose.pose.orientation.z = 0.0
target_pose.pose.orientation.w = 0.70729
# 设置机器臂当前的状态作为运动初始状态
arm.set_start_state_to_current_state()
# 设置机械臂终端运动的目标位姿
arm.set_pose_target(target_pose, end_effector_link)
# 规划运动路径
traj = arm.plan()
# 按照规划的运动路径控制机械臂运动
arm.execute(traj)
rospy.sleep(1)
# 控制机械臂回到初始化位置
arm.set_named_target('home')
arm.go()
# 关闭并退出moveit
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
MoveItIkDemo()
#include
#include
#include
int main(int argc, char **argv)
{
ros::init(argc, argv, "moveit_fk_demo");
ros::AsyncSpinner spinner(1);
spinner.start();
moveit::planning_interface::MoveGroupInterface arm("manipulator");
//获取终端link的名称
std::string end_effector_link = arm.getEndEffectorLink();
//设置目标位置所使用的参考坐标系
std::string reference_frame = "base_link";
arm.setPoseReferenceFrame(reference_frame);
//当运动规划失败后,允许重新规划
arm.allowReplanning(true);
//设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.setGoalPositionTolerance(0.001);
arm.setGoalOrientationTolerance(0.01);
//设置允许的最大速度和加速度
arm.setMaxAccelerationScalingFactor(0.2);
arm.setMaxVelocityScalingFactor(0.2);
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
// 设置机器人终端的目标位置
geometry_msgs::Pose target_pose;
target_pose.orientation.x = 0.70692;
target_pose.orientation.y = 0.0;
target_pose.orientation.z = 0.0;
target_pose.orientation.w = 0.70729;
target_pose.position.x = 0.2593;
target_pose.position.y = 0.0636;
target_pose.position.z = 0.1787;
// 设置机器臂当前的状态作为运动初始状态
arm.setStartStateToCurrentState();
arm.setPoseTarget(target_pose);
// 进行运动规划,计算机器人移动到目标的运动轨迹,此时只是计算出轨迹,并不会控制机械臂运动
moveit::planning_interface::MoveGroupInterface::Plan plan;
moveit::planning_interface::MoveItErrorCode success = arm.plan(plan);
ROS_INFO("Plan (pose goal) %s",success?"":"FAILED");
//让机械臂按照规划的轨迹开始运动。
if(success)
arm.execute(plan);
sleep(1);
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
ros::shutdown();
return 0;
}
#!/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('manipulator')
# 当运动规划失败后,允许重新规划
arm.allow_replanning(True)
# 设置目标位置所使用的参考坐标系
arm.set_pose_reference_frame('base_link')
# 设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.set_goal_position_tolerance(0.001)
arm.set_goal_orientation_tolerance(0.001)
# 设置允许的最大速度和加速度
arm.set_max_acceleration_scaling_factor(0.5)
arm.set_max_velocity_scaling_factor(0.5)
# 获取终端link的名称
end_effector_link = arm.get_end_effector_link()
# 控制机械臂先回到初始化位置
arm.set_named_target('home')
arm.go()
rospy.sleep(1)
# 获取当前位姿数据最为机械臂运动的起始位姿
start_pose = arm.get_current_pose(end_effector_link).pose
# 初始化路点列表
waypoints = []
# 将初始位姿加入路点列表
if cartesian:
waypoints.append(start_pose)
# 设置路点数据,并加入路点列表
wpose = deepcopy(start_pose)
wpose.position.z -= 0.2
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
wpose.position.x += 0.15
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
wpose.position.y += 0.1
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
wpose.position.x -= 0.15
wpose.position.y -= 0.1
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
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.")
rospy.sleep(1)
# 控制机械臂先回到初始化位置
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
#include
#include
#include
int main(int argc, char **argv)
{
ros::init(argc, argv, "moveit_cartesian_demo");
ros::AsyncSpinner spinner(1);
spinner.start();
moveit::planning_interface::MoveGroupInterface arm("manipulator");
//获取终端link的名称
std::string end_effector_link = arm.getEndEffectorLink();
//设置目标位置所使用的参考坐标系
std::string reference_frame = "base_link";
arm.setPoseReferenceFrame(reference_frame);
//当运动规划失败后,允许重新规划
arm.allowReplanning(true);
//设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.setGoalPositionTolerance(0.001);
arm.setGoalOrientationTolerance(0.01);
//设置允许的最大速度和加速度
arm.setMaxAccelerationScalingFactor(0.2);
arm.setMaxVelocityScalingFactor(0.2);
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
// 获取当前位姿数据最为机械臂运动的起始位姿
geometry_msgs::Pose start_pose = arm.getCurrentPose(end_effector_link).pose;
std::vector waypoints;
//将初始位姿加入路点列表
waypoints.push_back(start_pose);
start_pose.position.z -= 0.2;
waypoints.push_back(start_pose);
start_pose.position.x += 0.1;
waypoints.push_back(start_pose);
start_pose.position.y += 0.1;
waypoints.push_back(start_pose);
// 笛卡尔空间下的路径规划
moveit_msgs::RobotTrajectory trajectory;
const double jump_threshold = 0.0;
const double eef_step = 0.01;
double fraction = 0.0;
int maxtries = 100; //最大尝试规划次数
int attempts = 0; //已经尝试规划次数
while(fraction < 1.0 && attempts < maxtries)
{
fraction = arm.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
attempts++;
if(attempts % 10 == 0)
ROS_INFO("Still trying after %d attempts...", attempts);
}
if(fraction == 1)
{
ROS_INFO("Path computed successfully. Moving the arm.");
// 生成机械臂的运动规划数据
moveit::planning_interface::MoveGroupInterface::Plan plan;
plan.trajectory_ = trajectory;
// 执行运动
arm.execute(plan);
sleep(1);
}
else
{
ROS_INFO("Path planning failed with only %0.6f success after %d attempts.", fraction, maxtries);
}
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
ros::shutdown();
return 0;
}
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, sys
import thread, copy
import moveit_commander
from moveit_commander import RobotCommander, MoveGroupCommander, PlanningSceneInterface
from geometry_msgs.msg import PoseStamped, Pose
from moveit_msgs.msg import CollisionObject, AttachedCollisionObject, PlanningScene
from math import radians
from copy import deepcopy
class MoveAttachedObjectDemo:
def __init__(self):
# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)
# 初始化ROS节点
rospy.init_node('moveit_attached_object_demo')
# 初始化场景对象
scene = PlanningSceneInterface()
rospy.sleep(1)
# 初始化需要使用move group控制的机械臂中的arm group
arm = MoveGroupCommander('manipulator')
# 获取终端link的名称
end_effector_link = arm.get_end_effector_link()
# 设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.set_goal_position_tolerance(0.01)
arm.set_goal_orientation_tolerance(0.05)
# 当运动规划失败后,允许重新规划
arm.allow_replanning(True)
arm.set_planning_time(10)
# 控制机械臂回到初始化位置
arm.set_named_target('home')
arm.go()
# 移除场景中之前运行残留的物体
scene.remove_attached_object(end_effector_link, 'tool')
scene.remove_world_object('table')
scene.remove_world_object('target')
# 设置桌面的高度
table_ground = 0.6
# 设置table和tool的三维尺寸
table_size = [0.1, 0.7, 0.01]
tool_size = [0.2, 0.02, 0.02]
# 设置tool的位姿
p = PoseStamped()
p.header.frame_id = end_effector_link
p.pose.position.x = tool_size[0] / 2.0 - 0.025
p.pose.position.y = -0.015
p.pose.position.z = 0.0
p.pose.orientation.x = 0
p.pose.orientation.y = 0
p.pose.orientation.z = 0
p.pose.orientation.w = 1
# 将tool附着到机器人的终端
scene.attach_box(end_effector_link, 'tool', p, tool_size)
# 将table加入场景当中
table_pose = PoseStamped()
table_pose.header.frame_id = 'base_link'
table_pose.pose.position.x = 0.25
table_pose.pose.position.y = 0.0
table_pose.pose.position.z = table_ground + table_size[2] / 2.0
table_pose.pose.orientation.w = 1.0
scene.add_box('table', table_pose, table_size)
rospy.sleep(2)
# 更新当前的位姿
arm.set_start_state_to_current_state()
# 设置机械臂的目标位置,使用六轴的位置数据进行描述(单位:弧度)
joint_positions = [0.827228546495185, 0.29496592875743577, 1.1185644936946095, -0.7987583317769674, -0.18950024740190782, 0.11752152218233858]
arm.set_joint_value_target(joint_positions)
# 控制机械臂完成运动
arm.go()
rospy.sleep(1)
# 控制机械臂回到初始化位置
arm.set_named_target('home')
arm.go()
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
MoveAttachedObjectDemo()
另:随机运动(C++)
#include
#include
int main(int argc, char **argv)
{
ros::init(argc, argv, "moveit_random_demo");
ros::AsyncSpinner spinner(1);
spinner.start();
moveit::planning_interface::MoveGroupInterface arm("manipulator");
arm.setGoalJointTolerance(0.001);
arm.setMaxAccelerationScalingFactor(0.2);
arm.setMaxVelocityScalingFactor(0.2);
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
// 随机产生一个目标位置
arm.setRandomTarget();
// 开始运动规划,并且让机械臂移动到目标位置
arm.move();
sleep(1);
// 控制机械臂先回到初始化位置
arm.setNamedTarget("home");
arm.move();
sleep(1);
ros::shutdown();
return 0;
}