ThinkChat2.0新版上线,更智能更精彩,支持会话、画图、阅读、搜索等,送10W Token,即刻开启你的AI之旅 广告
## 函数 move_joints ### 功能 使机械臂在关节空间运动。 ### 参数 ``` def move_joints(self, joints) ``` joints为六个轴的角度(用弧度表示)。如果成功,则返回`Command has been successfully processed`,否则会返回报错信息: - 如没有校准,则返回`You need to calibrate the robot before sending a command` - 如超限位,则返回`Goal has been rejected : joint 1 not in range` 各个轴的限位是: ``` joint_limits: j1: min: -1.5708 max: 1.5708 j2: min: -1.5708 max: 0.5236 j3: min: -0.2967 max: 1.5710 j4: min: -2.0944 max: 2.0944 j5: min: -1.7453 max: 1.7453 j6: min: -2.5310 max: 2.5310 ``` ### 示例 move_joints是机械臂最基本的api,其调用方式如下: ```python #!/usr/bin/env python import rospy from gauss_python_api.gauss_api import Gauss def test_move_joint(gauss): joints = [1,0,0,0,0,0] try: message = gauss.move_joints(joints) except Exception as e: print e else: print message if __name__ == '__main__': rospy.init_node('gauss_move_joint') g = Gauss() test_move_joint(g) rospy.spin() ``` 对应的ROS action: ``` gauss@gauss-ros:~$ rostopic echo /gauss/commander/robot_action/goal header: seq: 1 stamp: secs: 1552892922 nsecs: 703941106 frame_id: '' goal_id: stamp: secs: 1552892922 nsecs: 703782081 id: "/gauss_move_joint-1-1552892922.704" goal: cmd: cmd_type: 1 joints: [1.0, 0.0, 0.0, 0.0, 0.0, 0.0] position: x: 0.0 y: 0.0 z: 0.0 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 ```