Appearance
网络与连接
在新的环境中,初次启动机器人,需要确定机器是否已经联网,在没有联网的状态下,部分机器人的功能将无法使用; 建议使用显示器+键鼠登入到orin进行联网设置;
使用显示器和键鼠
使用USB键鼠和DP线连到机器人orin大脑之后,按照Ubuntu系统的方式使机器人连上用户的wifi, 并将大脑orin 设置为固定IP,避免经常更换;
使用机器人AP热点
对于不方便接USB键鼠和HDMI屏幕的场景,也可以通过连接机器人自身的AP热点来配置机器人的网络; 机器人大脑默认的AP名称前缀为nav01ap的Wi-Fi,此Wi-Fi就是机器人大脑的AP热点,密码为88888888。
终端连接
完成机器人的网络配置之后,对于开发者而言,可能还需要使用终端登入大脑系统,支持如下方式登入:
- Linux系统内终端:如果已经使用USB和HDMI登入orin,可以直接使用Linux系统终端登入;
- 外部终端登入Linux:通过标准ssh协议登入orin Linux系统,ssh端口是22;
- 登入到demos容器:
- 在Linux终端内,支持使用docker exec -it navi_project-demos-1 bash
- 外部终端,可通过ssh协议登入demos,指令:ssh root@ip -p 2222,密码:naviai@2025
运行一个代码示例
首先进入到Orin的demos容器(docker exec -it navi_project-demos-1 bash)。navi_ws工作空间的结构如下
bash
├── build
├── devel
└── src
├── CMakeLists.txt
├── demos # cpp示例代码包
│ ├── CMakeLists.txt
│ ├── include
│ ├── package.xml
│ └── src
└── py_demos # python示例代码包
├── CMakeLists.txt
├── config
├── package.xml
└── scripts- 设置环境变量:
source /navi_ws/devel/setup.bash - 运行示例代码:
rosrun py_demos gesture_switch.py。效果是机器人左手做出拳头的手势,右手做出一的手势。
编写代码
为了方便用户开发,Orin/home/naviai/navi_project/containers/demos/user_code下的所有文件都映射到demos容器中,用户可以在Orin上编写代码,在容器中执行。
接下来我们将编写一个python程序控制机器人挥手。
新建python代码文件
新建wave.py文件
bash
touch ~/navi_project/containers/demos/user_code/wave.py
chmod +x ~/navi_project/containers/demos/user_code/wave.py写入如下代码
python
#!/usr/bin/env python3
import rospy
import yaml
import sys
import threading
from upperlimb.srv import MoveJByPath, MoveJByPathRequest
from upperlimb.msg import Joints
from std_srvs.srv import Trigger, TriggerRequest
def load_yaml_data(yaml_file):
"""Load service request data from YAML file."""
try:
with open(yaml_file, 'r', encoding='utf-8') as f:
return yaml.safe_load(f)
except Exception as e:
rospy.logerr(f"Failed to load YAML file: {e}")
sys.exit(1)
def main():
if len(sys.argv) != 2:
print(f"Usage: {sys.argv[0]} <request_data.yaml>")
sys.exit(1)
yaml_file = sys.argv[1]
rospy.init_node('wave_demo', anonymous=True)
data = load_yaml_data(yaml_file)
if 'path' not in data or 'time' not in data or 'arm_type' not in data:
rospy.logerr("YAML data is missing 'path', 'time', or 'arm_type' keys.")
sys.exit(1)
ARM_SERVICE_NAME = '/zj_humanoid/upperlimb/movej_by_path/right_arm'
GO_DOWN_SERVICE_NAME = '/zj_humanoid/upperlimb/go_down/right_arm'
rospy.loginfo(f"Waiting for service ...")
rospy.wait_for_service(ARM_SERVICE_NAME)
rospy.wait_for_service(GO_DOWN_SERVICE_NAME)
try:
service_proxy = rospy.ServiceProxy(ARM_SERVICE_NAME, MoveJByPath)
go_down_proxy = rospy.ServiceProxy(GO_DOWN_SERVICE_NAME, Trigger)
req = MoveJByPathRequest()
joint_msgs = []
for joint_data in data['path']:
if 'joint' in joint_data and isinstance(joint_data['joint'], list):
joint_msg = Joints()
joint_msg.joint = [float(j) for j in joint_data['joint']]
joint_msgs.append(joint_msg)
else:
rospy.logwarn(f"Skipping invalid joint data: {joint_data}")
req.path = joint_msgs
req.time = float(data['time'])
req.is_async = bool(data['is_async'])
req.arm_type = int(data['arm_type'])
rospy.loginfo(f"Calling service {ARM_SERVICE_NAME}...")
response = service_proxy(req)
rospy.loginfo(f"Response: {response}")
rospy.loginfo(f"Preparing to call {GO_DOWN_SERVICE_NAME} service...")
go_down_req = TriggerRequest()
go_down_response = go_down_proxy(go_down_req)
if go_down_response.success:
rospy.loginfo(f"{GO_DOWN_SERVICE_NAME} service successful. Message: {go_down_response.message}")
else:
rospy.logerr(f"{GO_DOWN_SERVICE_NAME} service failed. Message: {go_down_response.message}")
except rospy.ServiceException as e:
rospy.logerr(f"Service call failed: {e}")
sys.exit(1)
if __name__ == '__main__':
try:
main()
except rospy.ROSInterruptException:
pass新建yaml配置文件
新建wave.yaml文件用于存放关节轨迹数据
bash
touch ~/navi_project/containers/demos/user_code/wave.yaml获取关节数据
- 开启右臂示教模式
bash
rosservice call /zj_humanoid/upperlimb/teach_mode/enter "arm_type: 2"- 拖动右臂到目标位置,订阅
/zj_humanoid/upperlimb/joint_states话题查看实时关节数据
bash
rostopic echo /zj_humanoid/upperlimb/joint_states数据示例如下,position中的数据顺序与name中的关节名一一对应:
bash
name:
- Shoulder_Y_L
- Shoulder_X_L
- Shoulder_Z_L
- Elbow_L
- Wrist_Z_L
- Wrist_Y_L
- Wrist_X_L
- Shoulder_Y_R
- Shoulder_X_R
- Shoulder_Z_R
- Elbow_R
- Wrist_Z_R
- Wrist_Y_R
- Wrist_X_R
- Neck_Z
- Neck_Y
- A_Waist
position: [0.0, 0.174, 0.0, -0.087, 0.0, 0.0, 0.0, 0.0, -0.399, -0.499, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]- 记录不同姿态的关节角度数据,编辑
wave.yaml文件,填入轨迹路径点和其他参数
yaml
path:
- joint: [0.0, -0.4, -0.5, 0.0, 0.0, 0.0, 0.0] # 第一个目标位置
- joint: [0.0, -0.3, -0.6, 0.0, 0.0, 0.0, 0.0] # 第二个目标位置
- joint: [0.0, -0.4, -0.5, 0.0, 0.0, 0.0, 0.0] # 第三个目标位置
time: 8.0 # 轨迹执行总时间(秒)
is_async: false # 是否异步执行
arm_type: 2 # 臂类型:1-左臂,2-右臂,3-双臂- 关闭示教模式
bash
rosservice call /zj_humanoid/upperlimb/teach_mode/exit "arm_type: 2"配置CMakeLists.txt
由于~/navi_project/containers/demos/user_code中的代码映射到了demos容器中的py_demos包的scripts目录下,需要在/navi_ws/src/py_demos/CMakeLists.txt中添加安装配置。
编辑/navi_ws/src/py_demos/CMakeLists.txt,在catkin_install_python部分添加:
cmake
catkin_install_python(PROGRAMS
scripts/user_code/wave.py
# 其他已有的脚本...
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)重新编译工作空间
bash
cd /navi_ws
catkin_make设置环境变量
bash
source /navi_ws/devel/setup.bash运行程序
bash
rosrun py_demos wave.py ~/navi_project/containers/demos/user_code/wave.yaml或者直接使用python执行:
bash
python3 ~/navi_project/containers/demos/user_code/wave.py ~/navi_project/containers/demos/user_code/wave.yaml执行后,机器人右臂会按照yaml文件中定义的轨迹路径运动,完成后自动放下。