跳转到内容

6. 二次开发快速上手

本章节将通过几个简单的示例程序演示如何快速跑起第一个二次开发程序,对此建立一个基本认知。

快速上手教程以二次开发程序部署在 HDU 上且使用 Python venv 虚拟环境为例。

  1. 通过WiFi 确认IP并连接

需要开发机和机器人连接到同一个无线网络,从 AimMaster 的设置-无线局域网界面上获取机器人 ip,实际为HDU的 WiFi的 ip,ssh 连接上后再通过 10.42.10.12 可跳转到 MDU

推荐的程序部署目录为 /agibot/,机上磁盘清理模块会定时清理空间,该文件夹为白名单文件夹不会被清理。

程序、数据放置于其他路径可能造成分区写满、文件被误删等后果,请严格遵循使用 /agibot/ 目录的约定。

Terminal window
mkdir -p /agibot/data/home/agi/Desktop

如遇权限问题,可考虑使用如下命令进行文件夹创建

Terminal window
sudo mkdir -p /agibot/data/home/agi/Desktop
sudo chown -R agi:agi /agibot/data/home/agi
Terminal window
cd /agibot/data/home/agi/Desktop
python -m venv mydev
source mydev/bin/activate

后续示例都假设已创建虚拟环境并激活,不再重复此步骤。

本示例采用 HTTP 请求查询静默模式。

直接在 ORIN 命令行运行如下脚本:

curl --location --request POST 'http://10.42.10.10:59301/rpc/aimdk.protocol.AgentControlService/GetVoiceEnable' \
--header 'Content-Type: application/json' \
--data-raw '{}'

返回结果应如下所示(具体字段含义在后续接口章节中有详细解释):

{"header":{"code":"0","msg":"GetVoiceEnable successfully","trace_id":"","domin":""},"enable_voice":true}

6.3 获取机器人上肢关节状态示例

Section titled “6.3 获取机器人上肢关节状态示例”

将以下代码在 HDU 上保存为 /agibot/data/home/agi/Desktop/joint_state.py 文件。

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy
from sensor_msgs.msg import JointState
class JointStateSubscriber(Node):
def __init__(self, topic_name: str):
super().__init__("joint_state_subscriber")
self.topic_name = topic_name
qos_profile = QoSProfile(
history=QoSHistoryPolicy.KEEP_LAST, depth=10, reliability=QoSReliabilityPolicy.BEST_EFFORT
)
self.subscription = self.create_subscription(JointState, topic_name, self.listener_callback, qos_profile)
def listener_callback(self, msg: JointState):
self.get_logger().info(f"=== Received {self.topic_name} ===")
self.get_logger().info(f" header: {msg.header}")
self.get_logger().info(f" name: {msg.name}")
self.get_logger().info(f" position: {msg.position}")
self.get_logger().info(f" velocity: {msg.velocity}")
self.get_logger().info(f" effort: {msg.effort}")
def main(args=None):
rclpy.init(args=args)
joint_state_node = JointStateSubscriber("/motion/control/arm_joint_state")
try:
rclpy.spin(joint_state_node)
except KeyboardInterrupt:
pass
finally:
joint_state_node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":
main()

然后执行如下命令

export ROS_DOMAIN_ID=232
export FASTRTPS_DEFAULT_PROFILES_FILE=/agibot/software/v0/entry/cfg/ros_dds_configuration.xml
python3 /agibot/data/home/agi/Desktop/joint_state.py