## 函数 move_pose
### 功能
使机械臂在笛卡尔空间运动
注意:机械臂有自己的操作空间,move_pose调用机械臂逆解算法,可能没有逆解,最终返回错误码。所以需要自行判断move_pose的返回结果。
### 参数
```
def move_pose(self, x, y, z, roll, pitch, yaw)
```
只需要传入x、y、z、roll、pitch、yaw即可。如果成功,则返回`Command has been successfully processed`,否则会返回报错信息:
- 如超限位,则返回`Goal has been rejected : rot.z not in range.`
- 如逆解失败,则返回`Goal has been aborted : Moveit failed to execute plan.`
各个轴的限位是:
```
position_limits:
x:
min: 0.00
max: 0.461
y:
min: -0.461
max: 0.461
z:
min: 0.00
max: 0.711
rpy_limits:
roll:
min: -3.14159
max: 3.14159
pitch:
min: -3.14159
max: 3.14159
yaw:
min: -3.14159
max: 3.14159
```
### 示例
```python
#!/usr/bin/env python
import rospy
from gauss_python_api.gauss_api import Gauss
def test_move_pose(gauss):
pose = [300.5/1000, 4.0/1000, 338.3/1000, 0, 0, 0]
try:
message = gauss.move_pose(*pose)
except Exception as e:
print e
else:
print message
if __name__ == '__main__':
rospy.init_node('gauss_move_pose')
g = Gauss()
test_move_pose(g)
rospy.spin()
```
对应的ROS action:
```
gauss@gauss-ros:~$ rostopic echo /gauss/commander/robot_action/goal
header:
seq: 1
stamp:
secs: 1552893971
nsecs: 772053003
frame_id: ''
goal_id:
stamp:
secs: 1552893971
nsecs: 771902084
id: "/gauss_move_pose-1-1552893971.772"
goal:
cmd:
cmd_type: 2
joints: []
position:
x: 0.3005
y: 0.004
z: 0.3383
rpy:
roll: 0.0
pitch: 0.0
yaw: 0.0
shift:
axis_number: 0
value: 0.0
Trajectory:
trajectory_start:
joint_state:
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
name: []
position: []
velocity: []
effort: []
multi_dof_joint_state:
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
joint_names: []
transforms: []
twist: []
wrench: []
attached_collision_objects: []
is_diff: False
group_name: ''
trajectory:
joint_trajectory:
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
joint_names: []
points: []
multi_dof_joint_trajectory:
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
joint_names: []
points: []
pose_quat:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 0.0
saved_position_name: ''
saved_trajectory_id: 0
tool_cmd:
tool_id: 0
cmd_type: 0
gripper_close_speed: 0
gripper_open_speed: 0
activate: False
gpio: 0
```
- 引言
- 第一章 开关机和网络配置
- 开关机和网络连接
- 开机启动脚本
- 多机通信
- 安装必要的ROS包
- 第二章 软件架构
- 第三章 机械臂模型
- 第四章 Python API
- calibrate_auto
- learning_mode
- move_joints
- move_pose
- gripper
- air_vacuum_pump
- electromagnet
- 第五章 ROS接口
- 示教模式
- 关节空间
- 笛卡尔空间
- 运动规划
- 工具控制
- 自定义消息
- 重新校准
- 自动校准
- 硬件状态
- 第六章 参数说明
- rpi_ros_processes
- gauss_motors
- robot_command_validation
- stepper_params
- gauss_driver
- end_effectors
- 第七章 launch文件
- rpi_setup
- controllers
- robot_commander
- user_interface
- 第八章 视觉抓取
- 第九章 常见问题