mirror of
https://github.com/deepmodeling/Uni-Lab-OS
synced 2026-04-27 22:30:00 +00:00
修改角度读取方式
This commit is contained in:
@@ -132,10 +132,7 @@ class ResourceVisualization:
|
||||
new_dev.set("x",str(float(node["position"]["position"]["x"])/1000))
|
||||
new_dev.set("y",str(float(node["position"]["position"]["y"])/1000))
|
||||
new_dev.set("z",str(float(node["position"]["position"]["z"])/1000))
|
||||
if "rotation" in node["config"]:
|
||||
new_dev.set("rx",str(float(node["config"]["rotation"]["x"])))
|
||||
new_dev.set("ry",str(float(node["config"]["rotation"]["y"])))
|
||||
new_dev.set("r",str(float(node["config"]["rotation"]["z"])))
|
||||
|
||||
if "pose" in node:
|
||||
new_dev.set("x",str(float(node["pose"]["position"]["x"])/1000))
|
||||
new_dev.set("y",str(float(node["pose"]["position"]["y"])/1000))
|
||||
@@ -143,6 +140,10 @@ class ResourceVisualization:
|
||||
new_dev.set("rx",str(float(node["pose"]["rotation"]["x"])))
|
||||
new_dev.set("ry",str(float(node["pose"]["rotation"]["y"])))
|
||||
new_dev.set("r",str(float(node["pose"]["rotation"]["z"])))
|
||||
if "rotation" in node["config"]:
|
||||
new_dev.set("rx",str(float(node["config"]["rotation"]["x"])))
|
||||
new_dev.set("ry",str(float(node["config"]["rotation"]["y"])))
|
||||
new_dev.set("r",str(float(node["config"]["rotation"]["z"])))
|
||||
if "device_config" in node["config"]:
|
||||
for key, value in node["config"]["device_config"].items():
|
||||
new_dev.set(key, str(value))
|
||||
|
||||
@@ -1,5 +1,31 @@
|
||||
arm_slider_arm_controller:
|
||||
ros__parameters:
|
||||
command_interfaces:
|
||||
- position
|
||||
joints:
|
||||
- arm_slider_arm_base_joint
|
||||
- arm_slider_arm_link_1_joint
|
||||
- arm_slider_arm_link_2_joint
|
||||
- arm_slider_arm_link_3_joint
|
||||
- arm_slider_gripper_base_joint
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
arm_slider_gripper_controller:
|
||||
ros__parameters:
|
||||
command_interfaces:
|
||||
- position
|
||||
joints:
|
||||
- arm_slider_gripper_right_joint
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
arm_slider_arm_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
arm_slider_gripper_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
update_rate: 100
|
||||
|
||||
Reference in New Issue
Block a user