mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 04:51:10 +00:00
Dev v0.9.0 (#23)
Add high-level PLR functions Add Laiyu/Zhida driver support Fix ROS node discovery issues Add hostname and resource query support Fix ROS message conversion logic Support configuration via environment variables * Update README and MQTTClient for installation instructions and code improvements * feat: 支持local_config启动 add: 增加对crt path的说明,为传入config.py的相对路径 move: web component * add: registry description * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * feat: node_info_update srv fix: OTDeck cant create * close #12 feat: slave node registry * feat: show machine name fix: host node registry not uploaded * feat: add hplc registry * feat: add hplc registry * fix: hplc status typo * fix: devices/ * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * fix: device.class possible null * fix: HPLC additions with online service * fix: slave mode spin not working * fix: slave mode spin not working * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * feat: 多ProtocolNode 允许子设备ID相同 feat: 上报发现的ActionClient feat: Host重启动,通过discover机制要求slaveNode重新注册,实现信息及时上报 * feat: 支持env设置config * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * Device visualization (#14) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: missing hostname in devices_names fix: upload_file for model file * fix: missing paho-mqtt package bump version to 0.9.0 * fix startup add ResourceCreateFromOuter.action * fix type hint * update actions * update actions * host node add_resource_from_outer fix cmake list * pass device config to device class * add: bind_parent_ids to resource create action fix: message convert string * fix: host node should not be re_discovered * feat: resource tracker support dict * feat: add more necessary params * feat: fix boolean null in registry action data * feat: add outer resource * 编写mesh添加action * feat: append resource * add action * feat: vis 2d for plr * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate * Device visualization (#22) * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * add 3d visualization * 完成在main中启动设备可视化 完成在main中启动设备可视化,并输出物料ID:mesh的对应关系resource_model 添加物料模型管理类,遍历物料与resource_model,完成TF数据收集 * 完成TF发布 * 修改模型方向,在yaml中添加变换属性 * 添加物料tf变化时,发送topic到前端 另外修改了物料初始化的方法,防止在tf还未发布时提前建立物料模型与发布话题 * 添加关节发布节点与物料可视化节点进入unilab * 使用json启动plr与3D模型仿真 * 完成启动OT并联动rviz * 修复rviz位置问题, 修复rviz位置问题, 在无tf变动时减缓发送频率 在backend中添加物料跟随方法 * fix: running logic * fix: running logic * fix: missing ot * 在main中直接初始化republisher和物料的mesh节点 * 将joint_republisher和resource_mesh_manager添加进 main_slave_run.py中 * 编写mesh添加action * add action * fix * fix: browser on rviz * fix: cloud bridge error fallback to local * fix: salve auto run rviz * 初始化两个plate --------- Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: wznln <18435084+Xuwznln@users.noreply.github.com> * fix: multi channel * fix: aspirate * fix: aspirate * fix: aspirate * fix: aspirate * 提交 * fix: jobadd * fix: jobadd * fix: msg converter * tijiao --------- Co-authored-by: Harvey Que <Q-Query@outlook.com> Co-authored-by: zhangshixiang <@zhangshixiang> Co-authored-by: q434343 <73513873+q434343@users.noreply.github.com>
This commit is contained in:
@@ -7,11 +7,13 @@ from unilabos.utils import logger
|
||||
def start_backend(
|
||||
backend: str,
|
||||
devices_config: dict = {},
|
||||
resources_config: dict = {},
|
||||
resources_config: list = [],
|
||||
graph=None,
|
||||
controllers_config: dict = {},
|
||||
bridges=[],
|
||||
without_host: bool = False,
|
||||
visual: str = "None",
|
||||
resources_mesh_config: dict = {},
|
||||
**kwargs
|
||||
):
|
||||
if backend == "ros":
|
||||
@@ -29,7 +31,9 @@ def start_backend(
|
||||
|
||||
backend_thread = threading.Thread(
|
||||
target=main if not without_host else slave,
|
||||
args=(devices_config, resources_config, graph, controllers_config, bridges)
|
||||
args=(devices_config, resources_config, graph, controllers_config, bridges, visual, resources_mesh_config),
|
||||
name="backend_thread",
|
||||
daemon=True,
|
||||
)
|
||||
backend_thread.start()
|
||||
logger.info(f"Backend {backend} started.")
|
||||
|
||||
@@ -29,6 +29,8 @@ def job_add(req: JobAddReq) -> JobData:
|
||||
req.data['action'] = action_name
|
||||
if action_name == "execute_command_from_outer":
|
||||
action_kwargs = {"command": json.dumps(action_kwargs)}
|
||||
elif "command" in action_kwargs:
|
||||
action_kwargs = action_kwargs["command"]
|
||||
print(f"job_add:{req.device_id} {action_name} {action_kwargs}")
|
||||
HostNode.get_instance().send_goal(req.device_id, action_name=action_name, action_kwargs=action_kwargs, goal_uuid=req.job_id)
|
||||
return JobData(jobId=req.job_id)
|
||||
|
||||
@@ -1,19 +1,24 @@
|
||||
import argparse
|
||||
import asyncio
|
||||
import json
|
||||
import os
|
||||
import signal
|
||||
import sys
|
||||
import json
|
||||
import yaml
|
||||
import threading
|
||||
import time
|
||||
from copy import deepcopy
|
||||
|
||||
import yaml
|
||||
|
||||
# 首先添加项目根目录到路径
|
||||
current_dir = os.path.dirname(os.path.abspath(__file__))
|
||||
ilabos_dir = os.path.dirname(os.path.dirname(current_dir))
|
||||
if ilabos_dir not in sys.path:
|
||||
sys.path.append(ilabos_dir)
|
||||
unilabos_dir = os.path.dirname(os.path.dirname(current_dir))
|
||||
if unilabos_dir not in sys.path:
|
||||
sys.path.append(unilabos_dir)
|
||||
|
||||
from unilabos.config.config import load_config, BasicConfig, _update_config_from_env
|
||||
from unilabos.utils.banner_print import print_status, print_unilab_banner
|
||||
from unilabos.device_mesh.resource_visalization import ResourceVisualization
|
||||
|
||||
|
||||
def parse_args():
|
||||
@@ -65,12 +70,21 @@ def parse_args():
|
||||
help="信息页web服务的启动端口",
|
||||
)
|
||||
parser.add_argument(
|
||||
"--open_browser",
|
||||
type=bool,
|
||||
default=True,
|
||||
help="是否在启动时打开信息页",
|
||||
"--disable_browser",
|
||||
action='store_true',
|
||||
help="是否在启动时关闭信息页",
|
||||
)
|
||||
parser.add_argument(
|
||||
"--2d_vis",
|
||||
action='store_true',
|
||||
help="是否在pylabrobot实例启动时,同时启动可视化",
|
||||
)
|
||||
parser.add_argument(
|
||||
"--visual",
|
||||
choices=["rviz", "web", "disable"],
|
||||
default="disable",
|
||||
help="选择可视化工具: rviz, web",
|
||||
)
|
||||
|
||||
return parser.parse_args()
|
||||
|
||||
|
||||
@@ -101,6 +115,7 @@ def main():
|
||||
machine_name = os.popen("hostname").read().strip()
|
||||
machine_name = "".join([c if c.isalnum() or c == "_" else "_" for c in machine_name])
|
||||
BasicConfig.machine_name = machine_name
|
||||
BasicConfig.vis_2d_enable = args_dict["2d_vis"]
|
||||
|
||||
from unilabos.resources.graphio import (
|
||||
read_node_link_json,
|
||||
@@ -121,6 +136,7 @@ def main():
|
||||
# 注册表
|
||||
build_registry(args_dict["registry_path"])
|
||||
|
||||
devices_and_resources = None
|
||||
if args_dict["graph"] is not None:
|
||||
import unilabos.resources.graphio as graph_res
|
||||
graph_res.physical_setup_graph = (
|
||||
@@ -132,6 +148,7 @@ def main():
|
||||
args_dict["resources_config"] = initialize_resources(list(deepcopy(devices_and_resources).values()))
|
||||
args_dict["devices_config"] = dict_to_nested_dict(deepcopy(devices_and_resources), devices_only=False)
|
||||
# args_dict["resources_config"] = dict_to_tree(devices_and_resources, devices_only=False)
|
||||
|
||||
args_dict["graph"] = graph_res.physical_setup_graph
|
||||
else:
|
||||
if args_dict["devices"] is None or args_dict["resources"] is None:
|
||||
@@ -166,9 +183,28 @@ def main():
|
||||
signal.signal(signal.SIGINT, _exit)
|
||||
signal.signal(signal.SIGTERM, _exit)
|
||||
mqtt_client.start()
|
||||
|
||||
start_backend(**args_dict)
|
||||
start_server(port=args_dict.get("port", 8002), open_browser=args_dict.get("open_browser", False))
|
||||
args_dict["resources_mesh_config"] = {}
|
||||
# web visiualize 2D
|
||||
if args_dict["visual"] != "disable":
|
||||
enable_rviz = args_dict["visual"] == "rviz"
|
||||
if devices_and_resources is not None:
|
||||
resource_visualization = ResourceVisualization(devices_and_resources, args_dict["resources_config"] ,enable_rviz=enable_rviz)
|
||||
args_dict["resources_mesh_config"] = resource_visualization.resource_model
|
||||
start_backend(**args_dict)
|
||||
server_thread = threading.Thread(target=start_server, kwargs=dict(
|
||||
open_browser=not args_dict["disable_browser"]
|
||||
))
|
||||
server_thread.start()
|
||||
asyncio.set_event_loop(asyncio.new_event_loop())
|
||||
resource_visualization.start()
|
||||
while True:
|
||||
time.sleep(1)
|
||||
else:
|
||||
start_backend(**args_dict)
|
||||
start_server(open_browser=not args_dict["disable_browser"])
|
||||
else:
|
||||
start_backend(**args_dict)
|
||||
start_server(open_browser=not args_dict["disable_browser"])
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
import json
|
||||
import time
|
||||
import traceback
|
||||
import uuid
|
||||
|
||||
import paho.mqtt.client as mqtt
|
||||
@@ -35,7 +36,8 @@ class MQTTClient:
|
||||
self.client.on_disconnect = self._on_disconnect
|
||||
|
||||
def _on_log(self, client, userdata, level, buf):
|
||||
logger.info(f"[MQTT] log: {buf}")
|
||||
# logger.info(f"[MQTT] log: {buf}")
|
||||
pass
|
||||
|
||||
def _on_connect(self, client, userdata, flags, rc, properties=None):
|
||||
logger.info("[MQTT] Connected with result code " + str(rc))
|
||||
@@ -54,6 +56,12 @@ class MQTTClient:
|
||||
logger.debug("Payload:", json.dumps(payload_json, indent=2, ensure_ascii=False))
|
||||
if msg.topic == f"labs/{MQConfig.lab_id}/job/start/":
|
||||
logger.debug("job_add", type(payload_json), payload_json)
|
||||
if "data" not in payload_json:
|
||||
payload_json["data"] = {}
|
||||
if "action" in payload_json:
|
||||
payload_json["data"]["action"] = payload_json.pop("action")
|
||||
if "action_kwargs" in payload_json:
|
||||
payload_json["data"]["action_kwargs"] = payload_json.pop("action_kwargs")
|
||||
job_req = JobAddReq.model_validate(payload_json)
|
||||
data = job_add(job_req)
|
||||
return
|
||||
@@ -61,8 +69,10 @@ class MQTTClient:
|
||||
except json.JSONDecodeError as e:
|
||||
logger.error(f"[MQTT] JSON 解析错误: {e}")
|
||||
logger.error(f"[MQTT] Raw message: {msg.payload}")
|
||||
logger.error(traceback.format_exc())
|
||||
except Exception as e:
|
||||
logger.error(f"[MQTT] 处理消息时出错: {e}")
|
||||
logger.error(traceback.format_exc())
|
||||
|
||||
def _on_disconnect(self, client, userdata, rc, reasonCode=None, properties=None):
|
||||
if rc != 0:
|
||||
|
||||
@@ -9,6 +9,7 @@ from typing import List, Dict, Any, Optional
|
||||
import requests
|
||||
from unilabos.utils.log import info
|
||||
from unilabos.config.config import MQConfig, HTTPConfig
|
||||
from unilabos.utils import logger
|
||||
|
||||
|
||||
class HTTPClient:
|
||||
@@ -102,6 +103,30 @@ class HTTPClient:
|
||||
)
|
||||
return response
|
||||
|
||||
def upload_file(self, file_path: str, scene: str = "models") -> requests.Response:
|
||||
"""
|
||||
上传文件到服务器
|
||||
|
||||
使用multipart/form-data格式上传文件,类似curl -F "files=@filepath"
|
||||
|
||||
Args:
|
||||
file_path: 要上传的文件路径
|
||||
scene: 上传场景,可选值为"user"或"models",默认为"models"
|
||||
|
||||
Returns:
|
||||
Response: API响应对象
|
||||
"""
|
||||
with open(file_path, "rb") as file:
|
||||
files = {"files": file}
|
||||
logger.info(f"上传文件: {file_path} 到 {scene}")
|
||||
response = requests.post(
|
||||
f"{self.remote_addr}/api/account/file_upload/{scene}",
|
||||
files=files,
|
||||
headers={"Authorization": f"lab {self.auth}"},
|
||||
timeout=30, # 上传文件可能需要更长的超时时间
|
||||
)
|
||||
return response
|
||||
|
||||
|
||||
# 创建默认客户端实例
|
||||
http_client = HTTPClient()
|
||||
|
||||
@@ -8,7 +8,7 @@ import traceback
|
||||
from typing import Dict, Any, Type, TypedDict, Optional
|
||||
|
||||
from rclpy.action import ActionClient, ActionServer
|
||||
from rosidl_parser.definition import UnboundedSequence, NamespacedType, BasicType
|
||||
from rosidl_parser.definition import UnboundedSequence, NamespacedType, BasicType, UnboundedString
|
||||
|
||||
from unilabos.ros.msgs.message_converter import msg_converter_manager
|
||||
from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode
|
||||
@@ -74,7 +74,6 @@ def get_yaml_from_goal_type(goal_type) -> str:
|
||||
for ind, slot_info in enumerate(goal_type._fields_and_field_types.items()):
|
||||
slot_name, slot_type = slot_info
|
||||
type_info = goal_type.SLOT_TYPES[ind]
|
||||
default_value = "unknown"
|
||||
if isinstance(type_info, UnboundedSequence):
|
||||
inner_type = type_info.value_type
|
||||
if isinstance(inner_type, NamespacedType):
|
||||
@@ -83,8 +82,10 @@ def get_yaml_from_goal_type(goal_type) -> str:
|
||||
default_value = [get_ros_msg_instance_as_dict(type_class())]
|
||||
elif isinstance(inner_type, BasicType):
|
||||
default_value = [get_default_value_for_ros_type(inner_type.typename)]
|
||||
elif isinstance(inner_type, UnboundedString):
|
||||
default_value = [""]
|
||||
else:
|
||||
default_value = "unknown"
|
||||
default_value = []
|
||||
elif isinstance(type_info, NamespacedType):
|
||||
cls_name = ".".join(type_info.namespaces) + ":" + type_info.name
|
||||
type_class = msg_converter_manager.get_class(cls_name)
|
||||
@@ -93,6 +94,8 @@ def get_yaml_from_goal_type(goal_type) -> str:
|
||||
default_value = get_ros_msg_instance_as_dict(type_class())
|
||||
elif isinstance(type_info, BasicType):
|
||||
default_value = get_default_value_for_ros_type(type_info.typename)
|
||||
elif isinstance(type_info, UnboundedString):
|
||||
default_value = ""
|
||||
else:
|
||||
type_class = msg_converter_manager.search_class(slot_type, search_lower=True)
|
||||
if type_class is not None:
|
||||
|
||||
Reference in New Issue
Block a user