## 运动规划
接口文件: gauss/gauss_python_api/src/gauss_python_api/gauss_api.py
- 接口: gauss/commander/robot_action
- ROS 接口类型: Action
- 接口内容: RobotMoveAction
move接口可以完成如下的规划任务:
```
JOINTS = 1
POSE = 2
POSITION = 3
RPY = 4
SHIFT_POSE = 5
# TOOL = 6
# EXECUTE_TRAJ = 7
# POSE_QUAT = 8
# SAVED_POSITION =9
# SAVED_TRAJECTORY = 10
```
注意:Gauss机械臂提供了关节坐标系、直角坐标系的接口,暂未提供笛卡尔路径规划接口。
POSE、POSITION、RPY、SHIFT_POSE 等规划依赖于规划器和逆解器算法。如有发现规划失败,则需要考虑:
1. 是否超出了机械臂的可达范围
2. 更换OMPL所使用的插件: 配置文件在 ompl_planning.yaml
3. 考虑是否需要更换moveit规划器:https://moveit.ros.org/documentation/planners/
4. 考虑是否需要更换逆解器:ikfast、trac_ik等
示例代码参考`gauss/gauss_python_api/src/gauss_python_api/gauss_api.py`文件:
```python
def move_pose(self, x, y, z, roll, pitch, yaw):
goal = RobotMoveGoal()
goal.cmd.cmd_type = MoveCommandType.POSE
goal.cmd.position.x = x
goal.cmd.position.y = y
goal.cmd.position.z = z
goal.cmd.rpy.roll = roll
goal.cmd.rpy.pitch = pitch
goal.cmd.rpy.yaw = yaw
return self.execute_action('gauss/commander/robot_action', RobotMoveAction, goal)
def move_joints(self, joints):
goal = RobotMoveGoal()
goal.cmd.cmd_type = MoveCommandType.JOINTS
goal.cmd.joints = joints
return self.execute_action('gauss/commander/robot_action', RobotMoveAction, goal)
```
参考:
1、 https://bitbucket.org/traclabs/trac_ik/src/HEAD/trac_ik_kinematics_plugin/
- 引言
- 第一章 开关机和网络配置
- 开关机和网络连接
- 开机启动脚本
- 多机通信
- 安装必要的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
- 第八章 视觉抓取
- 第九章 常见问题