主要参考:
00 MoveIt
在之前的工作中,在启动moveit后,启动了RViz图形界面,然后拖动机械臂末端,再点击“plan”实现轨迹的规划,点击“execute"执行机械臂的运动。 而实际工作中大都是通过编程的方式控制,而不是Rviz的图形化控制。
在MoveIt中有三个主要的控制接口可实现机械臂进行控制,如图所示,。
c++使用move_group_interface;python使用moveit_commander。使用moveit控制机械臂时,把他们放入头文件。
01 准备工作:创建功能包
cd ~/ur_ws/src
catkin_create_pkg control_robot std_msgs rospy roscpp moveit_ros_planning_interface moveit_ros_move_group
roscd control_robot
mkdir scripts
touch demo.py
sudo chmod +x talker.py
说明:
- 使用
catkin_create_pkg 创建功能包,第一个参数是功能包名字,第二个参数是功能包的依赖。 后续如果想再给功能包添加其他依赖,需要在CMakeList.txt 中修改(在find_package 里), - 创建后的功能包里有
/src 文件夹了,这个用以放置c++文件; python文件需要创建/script 文件夹 - 使用
touch 语句新建文件 - 对于
python 文件,创建后需要把它修改为可执行文件; 对于c++ 文件,每次修改后都要catkin_make - 对于
python 文件,另一个需要特别注意的是在.py 文件的第一行要有:#!/usr/bin/env python
02 正运动学
2.1 python
import rospy, sys
import moveit_commander
class MoveItFkDemo:
def __init__(self):
moveit_commander.roscpp_initialize(sys.argv)
rospy.init_node('moveit_fk_demo', anonymous=True)
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()
rospy.sleep(1)
joint_positions = [0.391410, -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_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
try:
MoveItFkDemo()
except rospy.ROSInterruptException:
pass
说明:
- 对于ur机械臂,
Planning Group 是manipulator ,这个可以在rviz的界面中看到
arm = moveit_commander.MoveGroupCommander('manipulator')
joint_positions = [0.391410, -0.676384, -0.376217, 0.0, 1.052834, 0.454125]
arm.set_joint_value_target(joint_positions)
arm.go()
rospy.sleep(1)
2.2 c++
#include <ros/ros.h>
#include <moveit/move_group_interface/move_group_interface.h>
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.5);
arm.setMaxVelocityScalingFactor(0.5);
arm.setNamedTarget("home");
arm.move();
sleep(1);
double targetPose[6] = {0.391410, -0.676384, -0.376217, 0.0, 1.052834, 0.454125};
std::vector<double> 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;
}
说明:
arm.setJointValueTarget(joint_group_positions);
arm.move();
sleep(1);
- 开辟多线程
对于一些只订阅一个话题的简单节点来说,我们使用ros::spin() 进入接收循环,每当有订阅的话题发布时,进入回调函数接收和处理消息数据。 但是更多的时候,一个节点往往要接收和处理不同来源的数据,并且这些数据的产生频率也各不相同,当我们在一个回调函数里耗费太多时间时,会导致其他回调函数被阻塞,导致数据丢失。 这种场合需要给一个节点开辟多个线程,保证数据流的畅通。它有start() 和stop() 函数,并且在销毁的时候会自动停止。 其中,开辟多线程:
ros::AsyncSpinner spinner(1);
03 逆运动学
3.1 python
import rospy, sys
import moveit_commander
from geometry_msgs.msg import PoseStamped, Pose
class MoveItIkDemo:
def __init__(self):
moveit_commander.roscpp_initialize(sys.argv)
rospy.init_node('moveit_ik_demo')
arm = moveit_commander.MoveGroupCommander('manipulator')
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)
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_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
MoveItIkDemo()
3.2 c++
#include <string>
#include <ros/ros.h>
#include <moveit/move_group_interface/move_group_interface.h>
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");
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;
}
04 注意事项
? 对于仿真来说,无论是c++还是python,都是先运行gazebo、moveit和rviz(rviz可以不运行,只运行前两个),然后开始运行自己写的代码。
roslaunch ur_gazebo ur3_bringup.launch
roslaunch ur3_moveit_config ur3_moveit_planning_execution.launch sim:=true
roslaunch ur3_moveit_config moveit_rviz.launch rviz_config:=$(rospack find ur3_moveit_config)/launch/moveit.rviz
? ? 无论是c++还是python,都可能需要修改CMakeList.txt 添加依赖,如
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
moveit_ros_planning_interface
moveit_ros_move_group
)
? ? 对于c++,每次运行完成都要catkin_make; 另外建立完c++文件后,需要修改CMakeList.txt (这里文件名为demo.cpp )
add_executable(demo_node src/demo.cpp)
target_link_libraries(demo_node ${catkin_LIBRARIES})
? ? 对于python,需要注意的是一开始把py文件变为可执行文件
sudo chmod +x [文件名].py
然后在py文件开头加上如下语句:
如果其中有中文注释,再加上:
? ? 运行c++程序的时:
rosrun control_robot demo_node
运行python程序的时:
rosrun control_robot demo.py
05 其他参考代码和遇到的问题
https://blog.csdn.net/gyxx1998/article/details/118935792
|