agenticros 0.1.9 → 0.1.10

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
package/dist/menu.js CHANGED
@@ -60,7 +60,7 @@ export async function runMenu() {
60
60
  choices: [
61
61
  { name: "2-wheel AMR (camera + depth + LiDAR)", value: "sim-amr" },
62
62
  {
63
- name: "6-DOF arm (UR5e + MoveIt2) [needs ros-humble-moveit, ~400 MB]",
63
+ name: "6-DOF arm (UR5e-shaped, per-joint position control)",
64
64
  value: "sim-arm",
65
65
  },
66
66
  ],
package/dist/menu.js.map CHANGED
@@ -1 +1 @@
1
- {"version":3,"file":"menu.js","sourceRoot":"","sources":["../src/menu.ts"],"names":[],"mappings":"AAAA;;;;;;GAMG;AAEH,OAAO,EAAE,MAAM,EAAE,OAAO,EAAE,MAAM,mBAAmB,CAAC;AAEpD,OAAO,EAAE,SAAS,EAAE,MAAM,kBAAkB,CAAC;AAC7C,OAAO,EAAE,WAAW,EAAE,MAAM,oBAAoB,CAAC;AACjD,OAAO,EAAE,WAAW,EAAE,MAAM,oBAAoB,CAAC;AACjD,OAAO,EAAE,aAAa,EAAE,YAAY,EAAE,MAAM,sBAAsB,CAAC;AACnE,OAAO,EAAE,aAAa,EAAE,MAAM,sBAAsB,CAAC;AACrD,OAAO,EAAE,WAAW,EAAE,MAAM,oBAAoB,CAAC;AACjD,OAAO,EAAE,aAAa,EAAE,MAAM,sBAAsB,CAAC;AACrD,OAAO,EAAE,MAAM,EAAE,IAAI,EAAE,KAAK,EAAE,GAAG,EAAE,MAAM,kBAAkB,CAAC;AAC5D,OAAO,EAAE,SAAS,EAAE,SAAS,EAAE,MAAM,iBAAiB,CAAC;AAQvD,MAAM,CAAC,KAAK,UAAU,OAAO;IAC3B,IAAI,CAAC,KAAK,EAAE,CAAC;QACX,IAAI,CACF,uGAAuG,CACxG,CAAC;QACF,OAAO;IACT,CAAC;IAED,MAAM,CAAC,gDAAgD,CAAC,CAAC;IAEzD,MAAM,KAAK,GAAG,SAAS,EAAE,CAAC;IAC1B,IAAI,KAAK,CAAC,QAAQ,EAAE,CAAC;QACnB,MAAM,GAAG,GAAG,SAAS,CAAC,KAAK,CAAC,QAAQ,CAAC,CAAC;QACtC,GAAG,CAAC,cAAc,KAAK,CAAC,QAAQ,GAAG,GAAG,CAAC,CAAC,CAAC,KAAK,GAAG,GAAG,CAAC,CAAC,CAAC,EAAE,EAAE,CAAC,CAAC;IAC/D,CAAC;IAED,wEAAwE;IACxE,MAAM,WAAW,GAAG,MAAM,YAAY,EAAE,CAAC;IAEzC,MAAM,WAAW,GAAiB;QAChC,EAAE,IAAI,EAAE,wBAAwB,EAAE,KAAK,EAAE,MAAM,EAAE;QACjD,EAAE,IAAI,EAAE,wBAAwB,EAAE,KAAK,EAAE,KAAK,EAAE;QAChD,EAAE,IAAI,EAAE,0DAA0D,EAAE,KAAK,EAAE,MAAM,EAAE;QACnF,EAAE,IAAI,EAAE,iBAAiB,EAAE,KAAK,EAAE,MAAM,EAAE;QAC1C,EAAE,IAAI,EAAE,uBAAuB,EAAE,KAAK,EAAE,QAAQ,EAAE;QAClD,EAAE,IAAI,EAAE,4CAA4C,EAAE,KAAK,EAAE,QAAQ,EAAE;QACvE,EAAE,IAAI,EAAE,WAAW,EAAE,KAAK,EAAE,MAAM,EAAE;QACpC,EAAE,IAAI,EAAE,aAAa,EAAE,KAAK,EAAE,QAAQ,EAAE;QACxC,EAAE,IAAI,EAAE,MAAM,EAAE,KAAK,EAAE,MAAM,EAAE;KAChC,CAAC;IAEF,MAAM,OAAO,GAAiB,WAAW;QACvC,CAAC,CAAC;YACE,WAAW,CAAC,IAAI,CAAC,CAAC,CAAC,EAAE,EAAE,CAAC,CAAC,CAAC,KAAK,KAAK,MAAM,CAAE;YAC5C,GAAG,WAAW,CAAC,MAAM,CAAC,CAAC,CAAC,EAAE,EAAE,CAAC,CAAC,CAAC,KAAK,KAAK,MAAM,CAAC;SACjD;QACH,CAAC,CAAC,WAAW,CAAC;IAEhB,MAAM,MAAM,GAAG,MAAM,MAAM,CAAS;QAClC,OAAO,EAAE,4BAA4B;QACrC,OAAO;QACP,OAAO,EAAE,WAAW,CAAC,CAAC,CAAC,MAAM,CAAC,CAAC,CAAC,KAAK,CAAC,QAAQ,KAAK,SAAS,IAAI,KAAK,CAAC,QAAQ,KAAK,SAAS,CAAC,CAAC,CAAC,KAAK,CAAC,CAAC,CAAC,MAAM;KAC9G,CAAC,CAAC;IAEH,QAAQ,MAAM,EAAE,CAAC;QACf,KAAK,MAAM;YACT,MAAM,SAAS,CAAC,EAAE,MAAM,EAAE,MAAM,EAAE,CAAC,CAAC;YACpC,MAAM;QACR,KAAK,KAAK,CAAC,CAAC,CAAC;YACX,MAAM,GAAG,GAAG,MAAM,MAAM,CAAwB;gBAC9C,OAAO,EAAE,wBAAwB;gBACjC,OAAO,EAAE;oBACP,EAAE,IAAI,EAAE,sCAAsC,EAAE,KAAK,EAAE,SAAS,EAAE;oBAClE;wBACE,IAAI,EAAE,gEAAgE;wBACtE,KAAK,EAAE,SAAS;qBACjB;iBACF;gBACD,OAAO,EAAE,SAAS;aACnB,CAAC,CAAC;YACH,MAAM,IAAI,GAAG,MAAM,OAAO,CAAC,EAAE,OAAO,EAAE,YAAY,EAAE,OAAO,EAAE,KAAK,EAAE,CAAC,CAAC;YACtE,MAAM,SAAS,CAAC,EAAE,MAAM,EAAE,GAAG,EAAE,IAAI,EAAE,CAAC,CAAC;YACvC,MAAM;QACR,CAAC;QACD,KAAK,MAAM;YACT,MAAM,WAAW,CAAC,EAAE,CAAC,CAAC;YACtB,MAAM;QACR,KAAK,MAAM;YACT,MAAM,WAAW,CAAC,EAAE,CAAC,CAAC;YACtB,MAAM;QACR,KAAK,QAAQ;YACX,MAAM,aAAa,CAAC,EAAE,CAAC,CAAC;YACxB,MAAM;QACR,KAAK,QAAQ;YACX,MAAM,aAAa,CAAC,EAAE,MAAM,EAAE,MAAM,EAAE,CAAC,CAAC;YACxC,MAAM;QACR,KAAK,MAAM;YACT,MAAM,WAAW,CAAC,EAAE,MAAM,EAAE,SAAS,EAAE,CAAC,CAAC;YACzC,MAAM;QACR,KAAK,QAAQ;YACX,MAAM,aAAa,CAAC,EAAE,CAAC,CAAC;YACxB,MAAM;QACR,KAAK,MAAM,CAAC;QACZ;YACE,MAAM;IACV,CAAC;AACH,CAAC"}
1
+ {"version":3,"file":"menu.js","sourceRoot":"","sources":["../src/menu.ts"],"names":[],"mappings":"AAAA;;;;;;GAMG;AAEH,OAAO,EAAE,MAAM,EAAE,OAAO,EAAE,MAAM,mBAAmB,CAAC;AAEpD,OAAO,EAAE,SAAS,EAAE,MAAM,kBAAkB,CAAC;AAC7C,OAAO,EAAE,WAAW,EAAE,MAAM,oBAAoB,CAAC;AACjD,OAAO,EAAE,WAAW,EAAE,MAAM,oBAAoB,CAAC;AACjD,OAAO,EAAE,aAAa,EAAE,YAAY,EAAE,MAAM,sBAAsB,CAAC;AACnE,OAAO,EAAE,aAAa,EAAE,MAAM,sBAAsB,CAAC;AACrD,OAAO,EAAE,WAAW,EAAE,MAAM,oBAAoB,CAAC;AACjD,OAAO,EAAE,aAAa,EAAE,MAAM,sBAAsB,CAAC;AACrD,OAAO,EAAE,MAAM,EAAE,IAAI,EAAE,KAAK,EAAE,GAAG,EAAE,MAAM,kBAAkB,CAAC;AAC5D,OAAO,EAAE,SAAS,EAAE,SAAS,EAAE,MAAM,iBAAiB,CAAC;AAQvD,MAAM,CAAC,KAAK,UAAU,OAAO;IAC3B,IAAI,CAAC,KAAK,EAAE,CAAC;QACX,IAAI,CACF,uGAAuG,CACxG,CAAC;QACF,OAAO;IACT,CAAC;IAED,MAAM,CAAC,gDAAgD,CAAC,CAAC;IAEzD,MAAM,KAAK,GAAG,SAAS,EAAE,CAAC;IAC1B,IAAI,KAAK,CAAC,QAAQ,EAAE,CAAC;QACnB,MAAM,GAAG,GAAG,SAAS,CAAC,KAAK,CAAC,QAAQ,CAAC,CAAC;QACtC,GAAG,CAAC,cAAc,KAAK,CAAC,QAAQ,GAAG,GAAG,CAAC,CAAC,CAAC,KAAK,GAAG,GAAG,CAAC,CAAC,CAAC,EAAE,EAAE,CAAC,CAAC;IAC/D,CAAC;IAED,wEAAwE;IACxE,MAAM,WAAW,GAAG,MAAM,YAAY,EAAE,CAAC;IAEzC,MAAM,WAAW,GAAiB;QAChC,EAAE,IAAI,EAAE,wBAAwB,EAAE,KAAK,EAAE,MAAM,EAAE;QACjD,EAAE,IAAI,EAAE,wBAAwB,EAAE,KAAK,EAAE,KAAK,EAAE;QAChD,EAAE,IAAI,EAAE,0DAA0D,EAAE,KAAK,EAAE,MAAM,EAAE;QACnF,EAAE,IAAI,EAAE,iBAAiB,EAAE,KAAK,EAAE,MAAM,EAAE;QAC1C,EAAE,IAAI,EAAE,uBAAuB,EAAE,KAAK,EAAE,QAAQ,EAAE;QAClD,EAAE,IAAI,EAAE,4CAA4C,EAAE,KAAK,EAAE,QAAQ,EAAE;QACvE,EAAE,IAAI,EAAE,WAAW,EAAE,KAAK,EAAE,MAAM,EAAE;QACpC,EAAE,IAAI,EAAE,aAAa,EAAE,KAAK,EAAE,QAAQ,EAAE;QACxC,EAAE,IAAI,EAAE,MAAM,EAAE,KAAK,EAAE,MAAM,EAAE;KAChC,CAAC;IAEF,MAAM,OAAO,GAAiB,WAAW;QACvC,CAAC,CAAC;YACE,WAAW,CAAC,IAAI,CAAC,CAAC,CAAC,EAAE,EAAE,CAAC,CAAC,CAAC,KAAK,KAAK,MAAM,CAAE;YAC5C,GAAG,WAAW,CAAC,MAAM,CAAC,CAAC,CAAC,EAAE,EAAE,CAAC,CAAC,CAAC,KAAK,KAAK,MAAM,CAAC;SACjD;QACH,CAAC,CAAC,WAAW,CAAC;IAEhB,MAAM,MAAM,GAAG,MAAM,MAAM,CAAS;QAClC,OAAO,EAAE,4BAA4B;QACrC,OAAO;QACP,OAAO,EAAE,WAAW,CAAC,CAAC,CAAC,MAAM,CAAC,CAAC,CAAC,KAAK,CAAC,QAAQ,KAAK,SAAS,IAAI,KAAK,CAAC,QAAQ,KAAK,SAAS,CAAC,CAAC,CAAC,KAAK,CAAC,CAAC,CAAC,MAAM;KAC9G,CAAC,CAAC;IAEH,QAAQ,MAAM,EAAE,CAAC;QACf,KAAK,MAAM;YACT,MAAM,SAAS,CAAC,EAAE,MAAM,EAAE,MAAM,EAAE,CAAC,CAAC;YACpC,MAAM;QACR,KAAK,KAAK,CAAC,CAAC,CAAC;YACX,MAAM,GAAG,GAAG,MAAM,MAAM,CAAwB;gBAC9C,OAAO,EAAE,wBAAwB;gBACjC,OAAO,EAAE;oBACP,EAAE,IAAI,EAAE,sCAAsC,EAAE,KAAK,EAAE,SAAS,EAAE;oBAClE;wBACE,IAAI,EAAE,qDAAqD;wBAC3D,KAAK,EAAE,SAAS;qBACjB;iBACF;gBACD,OAAO,EAAE,SAAS;aACnB,CAAC,CAAC;YACH,MAAM,IAAI,GAAG,MAAM,OAAO,CAAC,EAAE,OAAO,EAAE,YAAY,EAAE,OAAO,EAAE,KAAK,EAAE,CAAC,CAAC;YACtE,MAAM,SAAS,CAAC,EAAE,MAAM,EAAE,GAAG,EAAE,IAAI,EAAE,CAAC,CAAC;YACvC,MAAM;QACR,CAAC;QACD,KAAK,MAAM;YACT,MAAM,WAAW,CAAC,EAAE,CAAC,CAAC;YACtB,MAAM;QACR,KAAK,MAAM;YACT,MAAM,WAAW,CAAC,EAAE,CAAC,CAAC;YACtB,MAAM;QACR,KAAK,QAAQ;YACX,MAAM,aAAa,CAAC,EAAE,CAAC,CAAC;YACxB,MAAM;QACR,KAAK,QAAQ;YACX,MAAM,aAAa,CAAC,EAAE,MAAM,EAAE,MAAM,EAAE,CAAC,CAAC;YACxC,MAAM;QACR,KAAK,MAAM;YACT,MAAM,WAAW,CAAC,EAAE,MAAM,EAAE,SAAS,EAAE,CAAC,CAAC;YACzC,MAAM;QACR,KAAK,QAAQ;YACX,MAAM,aAAa,CAAC,EAAE,CAAC,CAAC;YACxB,MAAM;QACR,KAAK,MAAM,CAAC;QACZ;YACE,MAAM;IACV,CAAC;AACH,CAAC"}
package/package.json CHANGED
@@ -1,6 +1,6 @@
1
1
  {
2
2
  "name": "agenticros",
3
- "version": "0.1.9",
3
+ "version": "0.1.10",
4
4
  "type": "module",
5
5
  "description": "AgenticROS - agentic AI for ROS-powered robots. Single CLI to launch real-robot or simulated demos, manage configuration, and inspect status.",
6
6
  "keywords": [
@@ -1,5 +1,5 @@
1
1
  {
2
- "packedAt": "2026-06-05T23:23:33.790Z",
2
+ "packedAt": "2026-06-06T13:54:42.821Z",
3
3
  "repo": "https://github.com/PlaiPin/agenticros",
4
4
  "note": "This directory is a snapshot of the agenticros monorepo source. `agenticros init` will copy it to ~/agenticros and run pnpm install + colcon build there.",
5
5
  "layout": {
@@ -1,9 +1,9 @@
1
1
  # agenticros_sim
2
2
 
3
3
  Gazebo Harmonic simulation assets for the AgenticROS project: an indoor world,
4
- a 2-wheel diff-drive AMR with a depth camera + 2D lidar + IMU, and a `ros_gz_
5
- bridge` config that exposes everything on the topic names the real-robot
6
- plugin already expects.
4
+ a 2-wheel diff-drive AMR (depth camera + 2D lidar + IMU), a 6-DOF UR5e-shaped
5
+ robotic arm, and a `ros_gz_bridge` config that exposes everything on the topic
6
+ names the real-robot plugin already expects.
7
7
 
8
8
  ## What's inside
9
9
 
@@ -11,13 +11,20 @@ plugin already expects.
11
11
  agenticros_sim/
12
12
  ├── worlds/agenticros_indoor.sdf 12 x 12 m indoor room with obstacles
13
13
  │ and one "person" target for follow-me
14
- ├── models/agenticros_amr/ 2-wheel diff-drive AMR with sensors
15
- │ ├── model.config
16
- │ └── model.sdf
14
+ ├── models/
15
+ │ ├── agenticros_amr/ 2-wheel diff-drive AMR with sensors
16
+ │ └── agenticros_arm/ 6-DOF UR5e-shaped robotic arm
17
+ ├── urdf/
18
+ │ ├── agenticros_amr.urdf.xacro URDF mirror for RViz (AMR)
19
+ │ └── agenticros_arm.urdf.xacro URDF mirror for RViz (arm)
17
20
  ├── config/
18
- │ ├── amr_bridge.yaml gz <-> ROS topic mapping
19
- └── amr_view.rviz RViz config showing camera, scan, TF
20
- ├── launch/sim_amr.launch.py One-stop launcher
21
+ │ ├── amr_bridge.yaml gz <-> ROS topic mapping (AMR)
22
+ ├── amr_view.rviz RViz config: camera, scan, TF
23
+ ├── arm_bridge.yaml gz <-> ROS topic mapping (arm)
24
+ │ └── arm_view.rviz RViz config: RobotModel + TF
25
+ ├── launch/
26
+ │ ├── sim_amr.launch.py One-stop launcher (AMR)
27
+ │ └── sim_arm.launch.py One-stop launcher (arm)
21
28
  ├── env-hooks/ Add the package's share/ to GZ_SIM_RESOURCE_PATH
22
29
  └── CMakeLists.txt + package.xml Standard ament_cmake skeleton
23
30
  ```
@@ -26,18 +33,50 @@ agenticros_sim/
26
33
 
27
34
  ```bash
28
35
  # Easiest: use the agenticros CLI (handles ROS sourcing + workspace build).
29
- agenticros up sim-amr # GUI
30
- agenticros up sim-amr --rviz # GUI + RViz panel
31
- agenticros up sim-amr --no-camera # (no effect for sim - flag is real-only)
36
+ agenticros up sim-amr # AMR: GUI
37
+ agenticros up sim-amr --rviz # AMR: GUI + RViz panel
38
+ agenticros up sim-arm # Arm: GUI
39
+ agenticros up sim-arm --rviz # Arm: GUI + RViz (RobotModel + TF)
32
40
 
33
- # Or run the launch file directly:
41
+ # Or run the launch files directly:
34
42
  cd ros2_ws && colcon build --symlink-install --packages-select agenticros_sim
35
43
  source install/setup.bash
36
44
  ros2 launch agenticros_sim sim_amr.launch.py
37
45
  ros2 launch agenticros_sim sim_amr.launch.py use_rviz:=true
38
46
  ros2 launch agenticros_sim sim_amr.launch.py gui:=false # headless
47
+ ros2 launch agenticros_sim sim_arm.launch.py
48
+ ros2 launch agenticros_sim sim_arm.launch.py use_rviz:=true
39
49
  ```
40
50
 
51
+ ## Arm topic layout
52
+
53
+ The arm exposes one position-command topic per joint plus the usual
54
+ `/joint_states`, `/tf`, and `/clock`. Send a target angle in radians as a
55
+ `std_msgs/Float64` and the PD controller drives the joint there.
56
+
57
+ | Topic | Type | Direction |
58
+ |------------------------------------|-------------------------------|-----------|
59
+ | `/arm/shoulder_pan/cmd_pos` | `std_msgs/msg/Float64` | ROS -> GZ |
60
+ | `/arm/shoulder_lift/cmd_pos` | `std_msgs/msg/Float64` | ROS -> GZ |
61
+ | `/arm/elbow/cmd_pos` | `std_msgs/msg/Float64` | ROS -> GZ |
62
+ | `/arm/wrist_1/cmd_pos` | `std_msgs/msg/Float64` | ROS -> GZ |
63
+ | `/arm/wrist_2/cmd_pos` | `std_msgs/msg/Float64` | ROS -> GZ |
64
+ | `/arm/wrist_3/cmd_pos` | `std_msgs/msg/Float64` | ROS -> GZ |
65
+ | `/joint_states` | `sensor_msgs/msg/JointState` | GZ -> ROS |
66
+ | `/tf`, `/tf_static` | `tf2_msgs/msg/TFMessage` | GZ -> ROS |
67
+ | `/clock` | `rosgraph_msgs/msg/Clock` | GZ -> ROS |
68
+
69
+ Example - wave the elbow back and forth from the command line:
70
+
71
+ ```bash
72
+ ros2 topic pub /arm/elbow/cmd_pos std_msgs/msg/Float64 'data: 1.0' --once
73
+ sleep 2
74
+ ros2 topic pub /arm/elbow/cmd_pos std_msgs/msg/Float64 'data: -0.5' --once
75
+ ```
76
+
77
+ The same via an MCP `ros2_publish` tool call from Claude / Codex / Gemini works
78
+ identically.
79
+
41
80
  ## Topic layout
42
81
 
43
82
  The bridge YAML deliberately matches the real-robot AgenticROS plugin's topic
@@ -0,0 +1,84 @@
1
+ # arm_bridge.yaml
2
+ #
3
+ # Bridge config for the 6-DOF agenticros_arm sim. Feeds ros_gz_bridge's
4
+ # parameter_bridge so Gazebo Harmonic topics produced by the arm's
5
+ # JointPositionController + JointStatePublisher + PosePublisher plugins
6
+ # are exposed as the ROS 2 topics agent code expects.
7
+ #
8
+ # Direction notation:
9
+ # GZ_TO_ROS — gazebo publishes, ROS subscribes (joint feedback, TF, clock)
10
+ # ROS_TO_GZ — ROS publishes, gazebo subscribes (joint commands)
11
+ # BIDIRECTIONAL — rarely needed
12
+ #
13
+ # Topic naming convention: /arm/<joint>/cmd_pos for joint commands. Same
14
+ # naming pattern across all six joints so a Claude / Codex / Gemini
15
+ # `ros2_publish` tool call only needs to vary the joint name.
16
+
17
+ # ---------------- Clock (GZ -> ROS) ----------------
18
+ - ros_topic_name: "/clock"
19
+ gz_topic_name: "/clock"
20
+ ros_type_name: "rosgraph_msgs/msg/Clock"
21
+ gz_type_name: "gz.msgs.Clock"
22
+ direction: GZ_TO_ROS
23
+
24
+ # ---------------- /tf (GZ -> ROS) ----------------
25
+ - ros_topic_name: "/tf"
26
+ gz_topic_name: "/model/agenticros_arm/pose"
27
+ ros_type_name: "tf2_msgs/msg/TFMessage"
28
+ gz_type_name: "gz.msgs.Pose_V"
29
+ direction: GZ_TO_ROS
30
+
31
+ - ros_topic_name: "/tf_static"
32
+ gz_topic_name: "/model/agenticros_arm/pose_static"
33
+ ros_type_name: "tf2_msgs/msg/TFMessage"
34
+ gz_type_name: "gz.msgs.Pose_V"
35
+ direction: GZ_TO_ROS
36
+
37
+ # ---------------- Joint feedback (GZ -> ROS) ----------------
38
+ # robot_state_publisher consumes this to update the URDF transforms in
39
+ # RViz and to publish per-link /tf entries. The gz topic name matches the
40
+ # <topic>joint_states</topic> field on the SDF's JointStatePublisher
41
+ # plugin (gz-sim treats that as the literal topic, no model prefix).
42
+ - ros_topic_name: "/joint_states"
43
+ gz_topic_name: "/joint_states"
44
+ ros_type_name: "sensor_msgs/msg/JointState"
45
+ gz_type_name: "gz.msgs.Model"
46
+ direction: GZ_TO_ROS
47
+
48
+ # ---------------- Joint position commands (ROS -> GZ) ----------------
49
+ # Send std_msgs/Float64 (radians) to any of these to drive a joint.
50
+ - ros_topic_name: "/arm/shoulder_pan/cmd_pos"
51
+ gz_topic_name: "/arm/shoulder_pan/cmd_pos"
52
+ ros_type_name: "std_msgs/msg/Float64"
53
+ gz_type_name: "gz.msgs.Double"
54
+ direction: ROS_TO_GZ
55
+
56
+ - ros_topic_name: "/arm/shoulder_lift/cmd_pos"
57
+ gz_topic_name: "/arm/shoulder_lift/cmd_pos"
58
+ ros_type_name: "std_msgs/msg/Float64"
59
+ gz_type_name: "gz.msgs.Double"
60
+ direction: ROS_TO_GZ
61
+
62
+ - ros_topic_name: "/arm/elbow/cmd_pos"
63
+ gz_topic_name: "/arm/elbow/cmd_pos"
64
+ ros_type_name: "std_msgs/msg/Float64"
65
+ gz_type_name: "gz.msgs.Double"
66
+ direction: ROS_TO_GZ
67
+
68
+ - ros_topic_name: "/arm/wrist_1/cmd_pos"
69
+ gz_topic_name: "/arm/wrist_1/cmd_pos"
70
+ ros_type_name: "std_msgs/msg/Float64"
71
+ gz_type_name: "gz.msgs.Double"
72
+ direction: ROS_TO_GZ
73
+
74
+ - ros_topic_name: "/arm/wrist_2/cmd_pos"
75
+ gz_topic_name: "/arm/wrist_2/cmd_pos"
76
+ ros_type_name: "std_msgs/msg/Float64"
77
+ gz_type_name: "gz.msgs.Double"
78
+ direction: ROS_TO_GZ
79
+
80
+ - ros_topic_name: "/arm/wrist_3/cmd_pos"
81
+ gz_topic_name: "/arm/wrist_3/cmd_pos"
82
+ ros_type_name: "std_msgs/msg/Float64"
83
+ gz_type_name: "gz.msgs.Double"
84
+ direction: ROS_TO_GZ
@@ -0,0 +1,109 @@
1
+ Panels:
2
+ - Class: rviz_common/Displays
3
+ Help Height: 0
4
+ Name: Displays
5
+ Property Tree Widget:
6
+ Expanded:
7
+ - /TF1
8
+ - /RobotModel1
9
+ Splitter Ratio: 0.5
10
+ Tree Height: 600
11
+ - Class: rviz_common/Views
12
+ Expanded:
13
+ - /Current View1
14
+ Name: Views
15
+ Splitter Ratio: 0.5
16
+ Visualization Manager:
17
+ Class: ""
18
+ Displays:
19
+ - Alpha: 0.5
20
+ Cell Size: 0.5
21
+ Class: rviz_default_plugins/Grid
22
+ Color: 160; 160; 164
23
+ Enabled: true
24
+ Line Style:
25
+ Line Width: 0.03
26
+ Value: Lines
27
+ Name: Grid
28
+ Normal Cell Count: 0
29
+ Offset:
30
+ X: 0
31
+ Y: 0
32
+ Z: 0
33
+ Plane: XY
34
+ Plane Cell Count: 12
35
+ Reference Frame: <Fixed Frame>
36
+ Value: true
37
+ - Class: rviz_default_plugins/TF
38
+ Enabled: true
39
+ Frame Timeout: 15
40
+ Frames:
41
+ All Enabled: true
42
+ Marker Scale: 0.15
43
+ Name: TF
44
+ Show Arrows: true
45
+ Show Axes: true
46
+ Show Names: true
47
+ Update Interval: 0
48
+ Value: true
49
+ - Alpha: 1
50
+ Class: rviz_default_plugins/RobotModel
51
+ Collision Enabled: false
52
+ Description File: ""
53
+ Description Source: Topic
54
+ Description Topic:
55
+ Depth: 5
56
+ Durability Policy: Volatile
57
+ History Policy: Keep Last
58
+ Reliability Policy: Reliable
59
+ Value: /robot_description
60
+ Enabled: true
61
+ Mass Properties:
62
+ Inertia: false
63
+ Mass: false
64
+ Name: RobotModel
65
+ TF Prefix: ""
66
+ Update Interval: 0
67
+ Value: true
68
+ Visual Enabled: true
69
+ Enabled: true
70
+ Global Options:
71
+ Background Color: 48; 48; 48
72
+ Fixed Frame: base_link
73
+ Frame Rate: 30
74
+ Name: root
75
+ Tools:
76
+ - Class: rviz_default_plugins/Interact
77
+ Hide Inactive Objects: true
78
+ - Class: rviz_default_plugins/MoveCamera
79
+ - Class: rviz_default_plugins/Select
80
+ - Class: rviz_default_plugins/FocusCamera
81
+ - Class: rviz_default_plugins/Measure
82
+ Line color: 128; 128; 0
83
+ Transformation:
84
+ Current:
85
+ Class: rviz_default_plugins/TF
86
+ Value: true
87
+ Views:
88
+ Current:
89
+ Class: rviz_default_plugins/Orbit
90
+ Distance: 2.5
91
+ Enable Stereo Rendering:
92
+ Stereo Eye Separation: 0.0599999987
93
+ Stereo Focal Distance: 1
94
+ Swap Stereo Eyes: false
95
+ Value: false
96
+ Focal Point:
97
+ X: 0.4
98
+ Y: 0
99
+ Z: 0.4
100
+ Focal Shape Fixed Size: true
101
+ Focal Shape Size: 0.05
102
+ Invert Z Axis: false
103
+ Name: Current View
104
+ Near Clip Distance: 0.01
105
+ Pitch: 0.35
106
+ Target Frame: base_link
107
+ Value: Orbit (rviz)
108
+ Yaw: 0.785
109
+ Saved: ~
@@ -0,0 +1,223 @@
1
+ """sim_arm.launch.py
2
+
3
+ Bring up the AgenticROS 6-DOF arm in Gazebo (Fortress / ign-gazebo 6 on
4
+ Humble Jetson, or Harmonic / gz-sim 8 on Jazzy) with full ROS-side
5
+ plumbing:
6
+ * gz sim agenticros_indoor.sdf (the world)
7
+ * ros_gz_sim create (spawn the arm)
8
+ * ros_gz_bridge parameter_bridge (gz <-> ROS topics)
9
+ * robot_state_publisher (URDF mirror) (for RViz RobotModel)
10
+ * Optional RViz (--rviz launch arg)
11
+
12
+ Joint commands are exposed as std_msgs/Float64 (radians) on:
13
+ /arm/shoulder_pan/cmd_pos
14
+ /arm/shoulder_lift/cmd_pos
15
+ /arm/elbow/cmd_pos
16
+ /arm/wrist_1/cmd_pos
17
+ /arm/wrist_2/cmd_pos
18
+ /arm/wrist_3/cmd_pos
19
+
20
+ Examples:
21
+ ros2 launch agenticros_sim sim_arm.launch.py
22
+ ros2 launch agenticros_sim sim_arm.launch.py use_rviz:=true
23
+ ros2 launch agenticros_sim sim_arm.launch.py gui:=false # headless
24
+ """
25
+
26
+ from __future__ import annotations
27
+
28
+ import os
29
+
30
+ from ament_index_python.packages import get_package_share_directory
31
+ from launch import LaunchContext, LaunchDescription
32
+ from launch.actions import (
33
+ DeclareLaunchArgument,
34
+ ExecuteProcess,
35
+ IncludeLaunchDescription,
36
+ OpaqueFunction,
37
+ TimerAction,
38
+ )
39
+ from launch.conditions import IfCondition
40
+ from launch.launch_description_sources import PythonLaunchDescriptionSource
41
+ from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution
42
+ from launch_ros.actions import Node
43
+ from launch_ros.parameter_descriptions import ParameterValue
44
+ from launch_ros.substitutions import FindPackageShare
45
+
46
+
47
+ PKG_NAME = "agenticros_sim"
48
+
49
+ # Default "home" pose, published once after spawn so the arm settles in a
50
+ # stable known configuration instead of whatever gravity happens to find:
51
+ # shoulder_pan = 0 (forward)
52
+ # shoulder_lift = -pi/2 (upper arm up)
53
+ # elbow = pi/2 (forearm horizontal, forming an L)
54
+ # wrist_* = 0
55
+ HOME_POSE = {
56
+ "shoulder_pan": 0.0,
57
+ "shoulder_lift": -1.5707963,
58
+ "elbow": 1.5707963,
59
+ "wrist_1": 0.0,
60
+ "wrist_2": 0.0,
61
+ "wrist_3": 0.0,
62
+ }
63
+
64
+
65
+ def generate_launch_description() -> LaunchDescription:
66
+ pkg_share = get_package_share_directory(PKG_NAME)
67
+ default_world = os.path.join(pkg_share, "worlds", "agenticros_indoor.sdf")
68
+ default_bridge = os.path.join(pkg_share, "config", "arm_bridge.yaml")
69
+ default_rviz = os.path.join(pkg_share, "config", "arm_view.rviz")
70
+ model_sdf = os.path.join(pkg_share, "models", "agenticros_arm", "model.sdf")
71
+ urdf_xacro = os.path.join(pkg_share, "urdf", "agenticros_arm.urdf.xacro")
72
+
73
+ world_arg = DeclareLaunchArgument(
74
+ "world", default_value=default_world,
75
+ description="SDF world file to load (absolute path).",
76
+ )
77
+ use_rviz_arg = DeclareLaunchArgument(
78
+ "use_rviz", default_value="false",
79
+ description="Open RViz with the arm view config.",
80
+ )
81
+ use_sim_time_arg = DeclareLaunchArgument(
82
+ "use_sim_time", default_value="true",
83
+ description="Tell ROS nodes to use /clock published by gz.",
84
+ )
85
+ # Spawn the arm well away from the AMR spawn point (which is 0,0) so users
86
+ # running the indoor world can see both side by side if curious.
87
+ x_arg = DeclareLaunchArgument("x", default_value="3.0", description="Arm spawn X (m)")
88
+ y_arg = DeclareLaunchArgument("y", default_value="0.0", description="Arm spawn Y (m)")
89
+ z_arg = DeclareLaunchArgument("z", default_value="0.0", description="Arm spawn Z (m)")
90
+ yaw_arg = DeclareLaunchArgument("yaw", default_value="0.0", description="Arm yaw (rad)")
91
+ bridge_arg = DeclareLaunchArgument(
92
+ "bridge_config_file", default_value=default_bridge,
93
+ description="ros_gz_bridge parameter_bridge config YAML.",
94
+ )
95
+ gui_arg = DeclareLaunchArgument(
96
+ "gui", default_value="true",
97
+ description="If 'false', run gz-sim headless (-s -r).",
98
+ )
99
+ rviz_config_arg = DeclareLaunchArgument(
100
+ "rviz_config", default_value=default_rviz,
101
+ description="RViz config path (used when use_rviz is true).",
102
+ )
103
+
104
+ # ---------- Spawn the arm ----------
105
+ spawn_arm = Node(
106
+ package="ros_gz_sim",
107
+ executable="create",
108
+ name="spawn_agenticros_arm",
109
+ output="screen",
110
+ arguments=[
111
+ "-name", "agenticros_arm",
112
+ "-file", model_sdf,
113
+ "-x", LaunchConfiguration("x"),
114
+ "-y", LaunchConfiguration("y"),
115
+ "-z", LaunchConfiguration("z"),
116
+ "-Y", LaunchConfiguration("yaw"),
117
+ ],
118
+ )
119
+
120
+ # ---------- gz <-> ROS bridge ----------
121
+ bridge = Node(
122
+ package="ros_gz_bridge",
123
+ executable="parameter_bridge",
124
+ name="agenticros_arm_bridge",
125
+ output="screen",
126
+ parameters=[{
127
+ "config_file": LaunchConfiguration("bridge_config_file"),
128
+ "qos_overrides./tf_static.publisher.durability": "transient_local",
129
+ "use_sim_time": LaunchConfiguration("use_sim_time"),
130
+ }],
131
+ )
132
+
133
+ # ---------- robot_state_publisher (URDF mirror of the SDF) ----------
134
+ # Without this, RViz only has TF axes and won't draw the arm. The URDF is
135
+ # purely for visualization; physics, joint controllers, and gravity all
136
+ # live in the SDF.
137
+ # NOTE: `Command(... on_stderr='ignore')` keeps xacro's "redefining global
138
+ # symbol: pi" warnings from aborting the launch.
139
+ robot_description = ParameterValue(
140
+ Command(["xacro ", urdf_xacro], on_stderr="ignore"), value_type=str,
141
+ )
142
+ rsp = Node(
143
+ package="robot_state_publisher",
144
+ executable="robot_state_publisher",
145
+ name="robot_state_publisher",
146
+ output="screen",
147
+ parameters=[{
148
+ "robot_description": robot_description,
149
+ "use_sim_time": LaunchConfiguration("use_sim_time"),
150
+ }],
151
+ )
152
+
153
+ # ---------- Redundant home-pose publisher ----------
154
+ # The SDF already sets <initial_position> on the joints and the
155
+ # JointPositionController plugins so the arm spawns at home pose and
156
+ # the controllers hold it there immediately. This timer is a safety
157
+ # net: if a user `gz service`-spawned a fresh arm from a controller
158
+ # config that didn't include initial_position, this still gets it
159
+ # into a sane pose.
160
+ #
161
+ # `ros2 topic pub --once` is unreliable: the publisher exits before
162
+ # discovery completes, so the bridge often drops the message.
163
+ # `--times 5 --rate 5` publishes 5 copies over 1 s, which is enough
164
+ # for the bridge subscription to come up and consume at least one.
165
+ home_publishers = [
166
+ ExecuteProcess(
167
+ cmd=[
168
+ "ros2", "topic", "pub", "--times", "5", "--rate", "5",
169
+ f"/arm/{joint}/cmd_pos", "std_msgs/msg/Float64",
170
+ f"{{data: {angle}}}",
171
+ ],
172
+ output="log",
173
+ )
174
+ for joint, angle in HOME_POSE.items()
175
+ ]
176
+ home_pose_action = TimerAction(period=8.0, actions=home_publishers)
177
+
178
+ # ---------- Optional RViz ----------
179
+ rviz = Node(
180
+ package="rviz2",
181
+ executable="rviz2",
182
+ name="rviz2",
183
+ output="screen",
184
+ condition=IfCondition(LaunchConfiguration("use_rviz")),
185
+ arguments=["-d", LaunchConfiguration("rviz_config")],
186
+ parameters=[{"use_sim_time": LaunchConfiguration("use_sim_time")}],
187
+ )
188
+
189
+ return LaunchDescription([
190
+ world_arg,
191
+ use_rviz_arg,
192
+ use_sim_time_arg,
193
+ x_arg, y_arg, z_arg, yaw_arg,
194
+ bridge_arg,
195
+ gui_arg,
196
+ rviz_config_arg,
197
+ OpaqueFunction(function=_launch_gz_sim),
198
+ spawn_arm,
199
+ bridge,
200
+ rsp,
201
+ home_pose_action,
202
+ rviz,
203
+ ])
204
+
205
+
206
+ def _launch_gz_sim(context: LaunchContext, *_, **__):
207
+ """Resolve launch args and emit the gz_sim IncludeLaunchDescription action."""
208
+ gui = context.launch_configurations.get("gui", "true").lower() == "true"
209
+ world = context.launch_configurations.get(
210
+ "world",
211
+ os.path.join(get_package_share_directory(PKG_NAME), "worlds", "agenticros_indoor.sdf"),
212
+ )
213
+ gz_args = f"-r {world}" if gui else f"-r -s --headless-rendering {world}"
214
+
215
+ gz_launch = IncludeLaunchDescription(
216
+ PythonLaunchDescriptionSource(
217
+ PathJoinSubstitution(
218
+ [FindPackageShare("ros_gz_sim"), "launch", "gz_sim.launch.py"]
219
+ )
220
+ ),
221
+ launch_arguments=[("gz_args", gz_args)],
222
+ )
223
+ return [gz_launch]
@@ -20,7 +20,7 @@
20
20
  lidar scan → /scan
21
21
  imu → /imu/data
22
22
  -->
23
- <sdf version="1.10">
23
+ <sdf version="1.9">
24
24
  <model name="agenticros_amr">
25
25
 
26
26
  <!-- ===================== Chassis ===================== -->
@@ -0,0 +1,26 @@
1
+ <?xml version="1.0"?>
2
+ <model>
3
+ <name>agenticros_arm</name>
4
+ <version>1.0</version>
5
+ <sdf version="1.10">model.sdf</sdf>
6
+ <author>
7
+ <name>AgenticROS</name>
8
+ <email>hello@agenticros.dev</email>
9
+ </author>
10
+ <description>
11
+ Six-DOF UR5e-shaped robotic arm for the AgenticROS Phase 3 simulation.
12
+ Approximates the UR5e joint topology (shoulder_pan, shoulder_lift, elbow,
13
+ wrist_1, wrist_2, wrist_3 + tool0 end-effector frame) using simple
14
+ cylindrical link geometry, gz-sim JointPositionController plugins per
15
+ joint, and PD gains tuned to hold the arm against gravity without
16
+ ros2_control or MoveIt2 in the loop.
17
+
18
+ Topic surface (Gazebo side; ros_gz_bridge re-emits as ROS topics):
19
+ /arm/JOINT/cmd_pos type=gz.msgs.Double ROS_TO_GZ
20
+ /joint_states type=gz.msgs.Model GZ_TO_ROS
21
+ /model/agenticros_arm/pose type=gz.msgs.Pose_V GZ_TO_ROS (to /tf)
22
+
23
+ Send a single joint angle as ROS std_msgs/Float64 (radians) to any
24
+ /arm/JOINT/cmd_pos topic and the controller drives the joint there.
25
+ </description>
26
+ </model>
@@ -0,0 +1,426 @@
1
+ <?xml version="1.0"?>
2
+ <!--
3
+ agenticros_arm/model.sdf
4
+
5
+ 6-DOF UR5e-shaped robotic arm for the AgenticROS Phase 3 demo.
6
+
7
+ Why "UR5e-shaped" rather than the actual UR description package:
8
+ * No apt deps. The ur_description package is ~50 MB and requires a
9
+ slew of ros-humble-ur-* trees we don't otherwise need. This file
10
+ gives the same visual silhouette and joint topology with nothing
11
+ but cylinders.
12
+ * Self-contained physics. All joint inertias, limits, and damping
13
+ are tuned here so the arm stays upright under gravity without
14
+ ros2_control or MoveIt2.
15
+ * Easy to author the URDF mirror (urdf/agenticros_arm.urdf.xacro)
16
+ because we control the link geometry directly.
17
+
18
+ Joint chain (matches the UR5e topology so MoveIt2 IK could be layered
19
+ on later in Phase 3b without changing the SDF):
20
+
21
+ base_link --shoulder_pan_joint (Z)--> shoulder_link
22
+ --shoulder_lift_joint (Y)--> upper_arm_link
23
+ --elbow_joint (Y)--> forearm_link
24
+ --wrist_1_joint (Y)--> wrist_1_link
25
+ --wrist_2_joint (Z)--> wrist_2_link
26
+ --wrist_3_joint (Y)--> wrist_3_link
27
+ --fixed --> tool0 (end-effector frame)
28
+
29
+ Control surface (Gazebo side; ros_gz_bridge re-emits as ROS topics):
30
+
31
+ cmd to /arm/JOINT/cmd_pos type=gz.msgs.Double ROS_TO_GZ
32
+ fb from /joint_states type=gz.msgs.Model GZ_TO_ROS
33
+ tf from /model/agenticros_arm/pose and /pose_static
34
+
35
+ Send a single joint angle as ROS std_msgs/Float64 to e.g.
36
+ /arm/shoulder_pan/cmd_pos and the JointPositionController plugin below
37
+ drives the joint to that angle with a PD loop (kp=500, kd=50). The
38
+ arm reaches the target in ~1-2 s and holds against gravity.
39
+
40
+ Limits:
41
+ shoulder_pan, elbow, wrist_ : +/-pi rad
42
+ shoulder_lift : +/-pi/2 rad (prevents self-collision)
43
+ velocity : 2 rad/s effort: 30 Nm
44
+
45
+ NOTE on physics tuning: link masses are heavier than the real UR5e
46
+ on purpose - higher inertia keeps PD control numerically stable on
47
+ the relatively coarse default gz physics step (1 ms). If you want a
48
+ snappier feel, drop the masses by 50% and bump kp to ~800.
49
+ -->
50
+ <sdf version="1.9">
51
+ <model name="agenticros_arm">
52
+
53
+ <!-- ============================================================
54
+ Static pedestal. world_joint pins this to the world so the
55
+ arm doesn't drift sideways when the wrist is moving.
56
+ ============================================================ -->
57
+ <link name="base_link">
58
+ <pose>0 0 0.075 0 0 0</pose>
59
+ <inertial>
60
+ <mass>10.0</mass>
61
+ <inertia>
62
+ <ixx>0.05</ixx><iyy>0.05</iyy><izz>0.05</izz>
63
+ <ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
64
+ </inertia>
65
+ </inertial>
66
+ <collision name="col">
67
+ <geometry><cylinder><radius>0.08</radius><length>0.15</length></cylinder></geometry>
68
+ </collision>
69
+ <visual name="vis">
70
+ <geometry><cylinder><radius>0.08</radius><length>0.15</length></cylinder></geometry>
71
+ <material>
72
+ <ambient>0.15 0.15 0.15 1</ambient>
73
+ <diffuse>0.20 0.20 0.20 1</diffuse>
74
+ </material>
75
+ </visual>
76
+ </link>
77
+
78
+ <joint name="world_joint" type="fixed">
79
+ <parent>world</parent>
80
+ <child>base_link</child>
81
+ </joint>
82
+
83
+ <!-- ============================================================
84
+ shoulder_link (rotated around Z by shoulder_pan_joint)
85
+ ============================================================ -->
86
+ <link name="shoulder_link">
87
+ <pose>0 0 0.205 0 0 0</pose>
88
+ <inertial>
89
+ <mass>3.0</mass>
90
+ <inertia>
91
+ <ixx>0.008</ixx><iyy>0.008</iyy><izz>0.005</izz>
92
+ <ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
93
+ </inertia>
94
+ </inertial>
95
+ <collision name="col">
96
+ <geometry><cylinder><radius>0.07</radius><length>0.10</length></cylinder></geometry>
97
+ </collision>
98
+ <visual name="vis">
99
+ <geometry><cylinder><radius>0.07</radius><length>0.10</length></cylinder></geometry>
100
+ <material>
101
+ <ambient>0.20 0.45 0.70 1</ambient>
102
+ <diffuse>0.25 0.50 0.75 1</diffuse>
103
+ </material>
104
+ </visual>
105
+ </link>
106
+
107
+ <joint name="shoulder_pan_joint" type="revolute">
108
+ <parent>base_link</parent>
109
+ <child>shoulder_link</child>
110
+ <pose>0 0 0.075 0 0 0</pose>
111
+ <axis>
112
+ <xyz>0 0 1</xyz>
113
+ <limit>
114
+ <lower>-3.14159</lower><upper>3.14159</upper>
115
+ <velocity>2.0</velocity><effort>30.0</effort>
116
+ </limit>
117
+ <dynamics><damping>2.0</damping><friction>0.5</friction></dynamics>
118
+ </axis>
119
+ </joint>
120
+
121
+ <!-- ============================================================
122
+ upper_arm_link (rotated around Y by shoulder_lift_joint)
123
+ The link's own frame has its long axis along +X so that
124
+ positive shoulder_lift swings the arm "up and forward".
125
+ ============================================================ -->
126
+ <link name="upper_arm_link">
127
+ <pose>0.20 0 0.255 0 1.5707963 0</pose>
128
+ <inertial>
129
+ <mass>4.0</mass>
130
+ <inertia>
131
+ <ixx>0.02</ixx><iyy>0.06</iyy><izz>0.06</izz>
132
+ <ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
133
+ </inertia>
134
+ </inertial>
135
+ <collision name="col">
136
+ <geometry><cylinder><radius>0.045</radius><length>0.40</length></cylinder></geometry>
137
+ </collision>
138
+ <visual name="vis">
139
+ <geometry><cylinder><radius>0.045</radius><length>0.40</length></cylinder></geometry>
140
+ <material>
141
+ <ambient>0.85 0.55 0.10 1</ambient>
142
+ <diffuse>0.95 0.60 0.10 1</diffuse>
143
+ </material>
144
+ </visual>
145
+ </link>
146
+
147
+ <joint name="shoulder_lift_joint" type="revolute">
148
+ <parent>shoulder_link</parent>
149
+ <child>upper_arm_link</child>
150
+ <pose>0 0 0.05 0 0 0</pose>
151
+ <axis>
152
+ <xyz>0 1 0</xyz>
153
+ <limit>
154
+ <lower>-1.5707</lower><upper>1.5707</upper>
155
+ <velocity>2.0</velocity><effort>30.0</effort>
156
+ </limit>
157
+ <dynamics><damping>2.0</damping><friction>0.5</friction></dynamics>
158
+ <!-- Home: -pi/2 rotates the upper arm UP so gravity loads less.
159
+ Without this the arm spawns horizontal and visibly sags
160
+ before the PD controller catches up. -->
161
+ <initial_position>-1.5707963</initial_position>
162
+ </axis>
163
+ </joint>
164
+
165
+ <!-- ============================================================
166
+ forearm_link (rotated around Y by elbow_joint)
167
+ ============================================================ -->
168
+ <link name="forearm_link">
169
+ <pose>0.575 0 0.255 0 1.5707963 0</pose>
170
+ <inertial>
171
+ <mass>2.5</mass>
172
+ <inertia>
173
+ <ixx>0.012</ixx><iyy>0.04</iyy><izz>0.04</izz>
174
+ <ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
175
+ </inertia>
176
+ </inertial>
177
+ <collision name="col">
178
+ <geometry><cylinder><radius>0.035</radius><length>0.35</length></cylinder></geometry>
179
+ </collision>
180
+ <visual name="vis">
181
+ <geometry><cylinder><radius>0.035</radius><length>0.35</length></cylinder></geometry>
182
+ <material>
183
+ <ambient>0.85 0.55 0.10 1</ambient>
184
+ <diffuse>0.95 0.60 0.10 1</diffuse>
185
+ </material>
186
+ </visual>
187
+ </link>
188
+
189
+ <joint name="elbow_joint" type="revolute">
190
+ <parent>upper_arm_link</parent>
191
+ <child>forearm_link</child>
192
+ <pose>0 0 0.20 0 0 0</pose>
193
+ <axis>
194
+ <xyz>0 1 0</xyz>
195
+ <limit>
196
+ <lower>-3.14159</lower><upper>3.14159</upper>
197
+ <velocity>2.0</velocity><effort>30.0</effort>
198
+ </limit>
199
+ <dynamics><damping>1.5</damping><friction>0.5</friction></dynamics>
200
+ <!-- Home: +pi/2 puts the forearm horizontal forming an L with the
201
+ upper arm (which is at -pi/2). This is the "ready to grasp"
202
+ pose; without it the elbow spawns straight and the arm sticks
203
+ out vertically. -->
204
+ <initial_position>1.5707963</initial_position>
205
+ </axis>
206
+ </joint>
207
+
208
+ <!-- ============================================================
209
+ wrist_1_link (rotated around Y by wrist_1_joint)
210
+ ============================================================ -->
211
+ <link name="wrist_1_link">
212
+ <pose>0.80 0 0.255 0 1.5707963 0</pose>
213
+ <inertial>
214
+ <mass>0.8</mass>
215
+ <inertia>
216
+ <ixx>0.001</ixx><iyy>0.001</iyy><izz>0.001</izz>
217
+ <ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
218
+ </inertia>
219
+ </inertial>
220
+ <collision name="col">
221
+ <geometry><cylinder><radius>0.032</radius><length>0.10</length></cylinder></geometry>
222
+ </collision>
223
+ <visual name="vis">
224
+ <geometry><cylinder><radius>0.032</radius><length>0.10</length></cylinder></geometry>
225
+ <material>
226
+ <ambient>0.20 0.45 0.70 1</ambient>
227
+ <diffuse>0.25 0.50 0.75 1</diffuse>
228
+ </material>
229
+ </visual>
230
+ </link>
231
+
232
+ <joint name="wrist_1_joint" type="revolute">
233
+ <parent>forearm_link</parent>
234
+ <child>wrist_1_link</child>
235
+ <pose>0 0 0.175 0 0 0</pose>
236
+ <axis>
237
+ <xyz>0 1 0</xyz>
238
+ <limit>
239
+ <lower>-3.14159</lower><upper>3.14159</upper>
240
+ <velocity>2.0</velocity><effort>15.0</effort>
241
+ </limit>
242
+ <dynamics><damping>1.0</damping><friction>0.3</friction></dynamics>
243
+ </axis>
244
+ </joint>
245
+
246
+ <!-- ============================================================
247
+ wrist_2_link (rotated around Z by wrist_2_joint)
248
+ ============================================================ -->
249
+ <link name="wrist_2_link">
250
+ <pose>0.875 0 0.255 0 0 0</pose>
251
+ <inertial>
252
+ <mass>0.6</mass>
253
+ <inertia>
254
+ <ixx>0.0008</ixx><iyy>0.0008</iyy><izz>0.0008</izz>
255
+ <ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
256
+ </inertia>
257
+ </inertial>
258
+ <collision name="col">
259
+ <geometry><cylinder><radius>0.030</radius><length>0.08</length></cylinder></geometry>
260
+ </collision>
261
+ <visual name="vis">
262
+ <geometry><cylinder><radius>0.030</radius><length>0.08</length></cylinder></geometry>
263
+ <material>
264
+ <ambient>0.85 0.55 0.10 1</ambient>
265
+ <diffuse>0.95 0.60 0.10 1</diffuse>
266
+ </material>
267
+ </visual>
268
+ </link>
269
+
270
+ <joint name="wrist_2_joint" type="revolute">
271
+ <parent>wrist_1_link</parent>
272
+ <child>wrist_2_link</child>
273
+ <pose>0 0 0.075 0 0 0</pose>
274
+ <axis>
275
+ <xyz>0 0 1</xyz>
276
+ <limit>
277
+ <lower>-3.14159</lower><upper>3.14159</upper>
278
+ <velocity>2.0</velocity><effort>15.0</effort>
279
+ </limit>
280
+ <dynamics><damping>1.0</damping><friction>0.3</friction></dynamics>
281
+ </axis>
282
+ </joint>
283
+
284
+ <!-- ============================================================
285
+ wrist_3_link (rotated around Y by wrist_3_joint).
286
+ Has a fixed end-effector frame `tool0` at the tip - this is
287
+ what MoveIt2 / IK code targets in Phase 3b.
288
+ ============================================================ -->
289
+ <link name="wrist_3_link">
290
+ <pose>0.945 0 0.255 0 1.5707963 0</pose>
291
+ <inertial>
292
+ <mass>0.4</mass>
293
+ <inertia>
294
+ <ixx>0.0004</ixx><iyy>0.0004</iyy><izz>0.0004</izz>
295
+ <ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
296
+ </inertia>
297
+ </inertial>
298
+ <collision name="col">
299
+ <geometry><cylinder><radius>0.026</radius><length>0.06</length></cylinder></geometry>
300
+ </collision>
301
+ <visual name="vis">
302
+ <geometry><cylinder><radius>0.026</radius><length>0.06</length></cylinder></geometry>
303
+ <material>
304
+ <ambient>0.20 0.45 0.70 1</ambient>
305
+ <diffuse>0.25 0.50 0.75 1</diffuse>
306
+ </material>
307
+ </visual>
308
+ <!-- Tip marker so users can see "this is where tool0 lives" -->
309
+ <visual name="tool0_tip">
310
+ <pose>0 0 0.04 0 0 0</pose>
311
+ <geometry><sphere><radius>0.015</radius></sphere></geometry>
312
+ <material>
313
+ <ambient>0.9 0.1 0.1 1</ambient>
314
+ <diffuse>1.0 0.1 0.1 1</diffuse>
315
+ </material>
316
+ </visual>
317
+ </link>
318
+
319
+ <joint name="wrist_3_joint" type="revolute">
320
+ <parent>wrist_2_link</parent>
321
+ <child>wrist_3_link</child>
322
+ <pose>0 0 0.04 0 0 0</pose>
323
+ <axis>
324
+ <xyz>0 1 0</xyz>
325
+ <limit>
326
+ <lower>-3.14159</lower><upper>3.14159</upper>
327
+ <velocity>2.0</velocity><effort>10.0</effort>
328
+ </limit>
329
+ <dynamics><damping>0.5</damping><friction>0.2</friction></dynamics>
330
+ </axis>
331
+ </joint>
332
+
333
+ <!-- ===================== Plugins ===================== -->
334
+
335
+ <!--
336
+ One JointPositionController per joint. Each subscribes to a gz topic
337
+ of the form /arm/<joint>/cmd_pos (gz.msgs.Double). ros_gz_bridge
338
+ then re-exposes each as a ROS std_msgs/Float64 of the same name.
339
+
340
+ PD gains are deliberately high so the arm holds against gravity
341
+ without an integral term (which can cause oscillation in gz's
342
+ relatively coarse default step).
343
+
344
+ Plugin filename:
345
+ We use the "ignition-gazebo-*" prefix (Fortress / ign-gazebo 6)
346
+ rather than the more modern "gz-sim-*" prefix because the
347
+ ros-humble-ros-gz-bridge that ships with Humble is linked
348
+ against Fortress (libignition-msgs8 / libignition-transport11).
349
+ Fortress *does* ship a backward-compat shim that maps
350
+ "gz-sim-diff-drive-system" -> the Fortress library, which is
351
+ why agenticros_amr's diff-drive plugin works under the
352
+ gz-sim-* name; but no equivalent shim exists for the joint
353
+ position controller. Using the Fortress-native filename here
354
+ is the only one that loads reliably on Jetson Humble.
355
+
356
+ If you migrate this stack to Jazzy / Harmonic later, switch
357
+ the six filenames below to "gz-sim-joint-position-controller-system".
358
+ -->
359
+ <plugin filename="ignition-gazebo-joint-position-controller-system"
360
+ name="gz::sim::systems::JointPositionController">
361
+ <joint_name>shoulder_pan_joint</joint_name>
362
+ <topic>/arm/shoulder_pan/cmd_pos</topic>
363
+ <p_gain>800</p_gain><d_gain>80</d_gain><i_gain>0</i_gain>
364
+ <cmd_max>100</cmd_max><cmd_min>-100</cmd_min>
365
+ </plugin>
366
+ <plugin filename="ignition-gazebo-joint-position-controller-system"
367
+ name="gz::sim::systems::JointPositionController">
368
+ <joint_name>shoulder_lift_joint</joint_name>
369
+ <topic>/arm/shoulder_lift/cmd_pos</topic>
370
+ <p_gain>1200</p_gain><d_gain>120</d_gain><i_gain>0</i_gain>
371
+ <cmd_max>100</cmd_max><cmd_min>-100</cmd_min>
372
+ <!-- Match the joint's <initial_position> so the controller's first
373
+ setpoint isn't 0 (which would jerk the arm down at startup). -->
374
+ <initial_position>-1.5707963</initial_position>
375
+ </plugin>
376
+ <plugin filename="ignition-gazebo-joint-position-controller-system"
377
+ name="gz::sim::systems::JointPositionController">
378
+ <joint_name>elbow_joint</joint_name>
379
+ <topic>/arm/elbow/cmd_pos</topic>
380
+ <p_gain>800</p_gain><d_gain>80</d_gain><i_gain>0</i_gain>
381
+ <cmd_max>80</cmd_max><cmd_min>-80</cmd_min>
382
+ <initial_position>1.5707963</initial_position>
383
+ </plugin>
384
+ <plugin filename="ignition-gazebo-joint-position-controller-system"
385
+ name="gz::sim::systems::JointPositionController">
386
+ <joint_name>wrist_1_joint</joint_name>
387
+ <topic>/arm/wrist_1/cmd_pos</topic>
388
+ <p_gain>400</p_gain><d_gain>40</d_gain><i_gain>0</i_gain>
389
+ <cmd_max>15</cmd_max><cmd_min>-15</cmd_min>
390
+ </plugin>
391
+ <plugin filename="ignition-gazebo-joint-position-controller-system"
392
+ name="gz::sim::systems::JointPositionController">
393
+ <joint_name>wrist_2_joint</joint_name>
394
+ <topic>/arm/wrist_2/cmd_pos</topic>
395
+ <p_gain>300</p_gain><d_gain>30</d_gain><i_gain>0</i_gain>
396
+ <cmd_max>15</cmd_max><cmd_min>-15</cmd_min>
397
+ </plugin>
398
+ <plugin filename="ignition-gazebo-joint-position-controller-system"
399
+ name="gz::sim::systems::JointPositionController">
400
+ <joint_name>wrist_3_joint</joint_name>
401
+ <topic>/arm/wrist_3/cmd_pos</topic>
402
+ <p_gain>200</p_gain><d_gain>20</d_gain><i_gain>0</i_gain>
403
+ <cmd_max>10</cmd_max><cmd_min>-10</cmd_min>
404
+ </plugin>
405
+
406
+ <!-- Publishes /joint_states (used by robot_state_publisher + RViz). -->
407
+ <plugin filename="gz-sim-joint-state-publisher-system"
408
+ name="gz::sim::systems::JointStatePublisher">
409
+ <topic>joint_states</topic>
410
+ </plugin>
411
+
412
+ <!-- Publishes each link's pose as /tf so RViz can render motion. -->
413
+ <plugin filename="gz-sim-pose-publisher-system"
414
+ name="gz::sim::systems::PosePublisher">
415
+ <publish_link_pose>true</publish_link_pose>
416
+ <publish_sensor_pose>false</publish_sensor_pose>
417
+ <publish_collision_pose>false</publish_collision_pose>
418
+ <publish_visual_pose>false</publish_visual_pose>
419
+ <publish_nested_model_pose>false</publish_nested_model_pose>
420
+ <use_pose_vector_msg>true</use_pose_vector_msg>
421
+ <static_publisher>true</static_publisher>
422
+ <static_update_frequency>1</static_update_frequency>
423
+ </plugin>
424
+
425
+ </model>
426
+ </sdf>
@@ -0,0 +1,205 @@
1
+ <?xml version="1.0"?>
2
+ <!--
3
+ agenticros_arm.urdf.xacro
4
+
5
+ URDF mirror of models/agenticros_arm/model.sdf, fed to robot_state_publisher
6
+ so RViz's RobotModel display can render the arm. The forward-kinematics
7
+ topology MUST match the SDF link-by-link or RViz will draw the arm in the
8
+ wrong pose:
9
+
10
+ base_link -> shoulder_pan_joint -> shoulder_link
11
+ -> shoulder_lift_joint -> upper_arm_link
12
+ -> elbow_joint -> forearm_link
13
+ -> wrist_1_joint -> wrist_1_link
14
+ -> wrist_2_joint -> wrist_2_link
15
+ -> wrist_3_joint -> wrist_3_link
16
+ -> fixed -> tool0
17
+
18
+ Conventions:
19
+ * Each joint origin is expressed in its PARENT link's frame.
20
+ * Cylinder visuals are drawn along the link's local +Z by default; we
21
+ rotate them where needed to lay them flat along +X (matching how the
22
+ SDF orients each link via its <pose>).
23
+ * Joint axes match the SDF exactly (Z for pan/wrist_2, Y for the rest).
24
+ * Joint limits match the SDF; URDF doesn't really use them for
25
+ visualization but MoveIt2 (Phase 3b) will.
26
+
27
+ Physics, sensors, gravity tuning, and PD gains all live in the SDF; this
28
+ file is purely for visualization in RViz.
29
+ -->
30
+ <robot name="agenticros_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
31
+
32
+ <!-- ===== material palette (matches the SDF colours) ===== -->
33
+ <material name="agros_dark"> <color rgba="0.20 0.20 0.20 1"/></material>
34
+ <material name="agros_blue"> <color rgba="0.25 0.50 0.75 1"/></material>
35
+ <material name="agros_orange"><color rgba="0.95 0.60 0.10 1"/></material>
36
+ <material name="agros_red"> <color rgba="1.00 0.10 0.10 1"/></material>
37
+
38
+ <!-- ============================================================
39
+ base_link (static pedestal, fixed to world)
40
+ ============================================================ -->
41
+ <link name="base_link">
42
+ <visual>
43
+ <origin xyz="0 0 0.075" rpy="0 0 0"/>
44
+ <geometry><cylinder radius="0.08" length="0.15"/></geometry>
45
+ <material name="agros_dark"/>
46
+ </visual>
47
+ <collision>
48
+ <origin xyz="0 0 0.075" rpy="0 0 0"/>
49
+ <geometry><cylinder radius="0.08" length="0.15"/></geometry>
50
+ </collision>
51
+ <inertial>
52
+ <mass value="10.0"/>
53
+ <inertia ixx="0.05" iyy="0.05" izz="0.05" ixy="0" ixz="0" iyz="0"/>
54
+ </inertial>
55
+ </link>
56
+
57
+ <!-- ============================================================
58
+ shoulder_link (rotated around Z)
59
+ ============================================================ -->
60
+ <link name="shoulder_link">
61
+ <visual>
62
+ <origin xyz="0 0 0" rpy="0 0 0"/>
63
+ <geometry><cylinder radius="0.07" length="0.10"/></geometry>
64
+ <material name="agros_blue"/>
65
+ </visual>
66
+ <inertial>
67
+ <mass value="3.0"/>
68
+ <inertia ixx="0.008" iyy="0.008" izz="0.005" ixy="0" ixz="0" iyz="0"/>
69
+ </inertial>
70
+ </link>
71
+ <joint name="shoulder_pan_joint" type="revolute">
72
+ <parent link="base_link"/>
73
+ <child link="shoulder_link"/>
74
+ <origin xyz="0 0 0.205" rpy="0 0 0"/>
75
+ <axis xyz="0 0 1"/>
76
+ <limit lower="-3.14159" upper="3.14159" velocity="2.0" effort="30.0"/>
77
+ </joint>
78
+
79
+ <!-- ============================================================
80
+ upper_arm_link (rotated around Y) - laid along +X
81
+ ============================================================ -->
82
+ <link name="upper_arm_link">
83
+ <visual>
84
+ <origin xyz="0.20 0 0" rpy="0 1.5707963 0"/>
85
+ <geometry><cylinder radius="0.045" length="0.40"/></geometry>
86
+ <material name="agros_orange"/>
87
+ </visual>
88
+ <inertial>
89
+ <mass value="4.0"/>
90
+ <inertia ixx="0.02" iyy="0.06" izz="0.06" ixy="0" ixz="0" iyz="0"/>
91
+ </inertial>
92
+ </link>
93
+ <joint name="shoulder_lift_joint" type="revolute">
94
+ <parent link="shoulder_link"/>
95
+ <child link="upper_arm_link"/>
96
+ <origin xyz="0 0 0.05" rpy="0 0 0"/>
97
+ <axis xyz="0 1 0"/>
98
+ <limit lower="-1.5707" upper="1.5707" velocity="2.0" effort="30.0"/>
99
+ </joint>
100
+
101
+ <!-- ============================================================
102
+ forearm_link (rotated around Y)
103
+ ============================================================ -->
104
+ <link name="forearm_link">
105
+ <visual>
106
+ <origin xyz="0.175 0 0" rpy="0 1.5707963 0"/>
107
+ <geometry><cylinder radius="0.035" length="0.35"/></geometry>
108
+ <material name="agros_orange"/>
109
+ </visual>
110
+ <inertial>
111
+ <mass value="2.5"/>
112
+ <inertia ixx="0.012" iyy="0.04" izz="0.04" ixy="0" ixz="0" iyz="0"/>
113
+ </inertial>
114
+ </link>
115
+ <joint name="elbow_joint" type="revolute">
116
+ <parent link="upper_arm_link"/>
117
+ <child link="forearm_link"/>
118
+ <origin xyz="0.40 0 0" rpy="0 0 0"/>
119
+ <axis xyz="0 1 0"/>
120
+ <limit lower="-3.14159" upper="3.14159" velocity="2.0" effort="30.0"/>
121
+ </joint>
122
+
123
+ <!-- ============================================================
124
+ wrist_1_link (rotated around Y)
125
+ ============================================================ -->
126
+ <link name="wrist_1_link">
127
+ <visual>
128
+ <origin xyz="0.05 0 0" rpy="0 1.5707963 0"/>
129
+ <geometry><cylinder radius="0.032" length="0.10"/></geometry>
130
+ <material name="agros_blue"/>
131
+ </visual>
132
+ <inertial>
133
+ <mass value="0.8"/>
134
+ <inertia ixx="0.001" iyy="0.001" izz="0.001" ixy="0" ixz="0" iyz="0"/>
135
+ </inertial>
136
+ </link>
137
+ <joint name="wrist_1_joint" type="revolute">
138
+ <parent link="forearm_link"/>
139
+ <child link="wrist_1_link"/>
140
+ <origin xyz="0.35 0 0" rpy="0 0 0"/>
141
+ <axis xyz="0 1 0"/>
142
+ <limit lower="-3.14159" upper="3.14159" velocity="2.0" effort="15.0"/>
143
+ </joint>
144
+
145
+ <!-- ============================================================
146
+ wrist_2_link (rotated around Z)
147
+ ============================================================ -->
148
+ <link name="wrist_2_link">
149
+ <visual>
150
+ <origin xyz="0 0 0.04" rpy="0 0 0"/>
151
+ <geometry><cylinder radius="0.030" length="0.08"/></geometry>
152
+ <material name="agros_orange"/>
153
+ </visual>
154
+ <inertial>
155
+ <mass value="0.6"/>
156
+ <inertia ixx="0.0008" iyy="0.0008" izz="0.0008" ixy="0" ixz="0" iyz="0"/>
157
+ </inertial>
158
+ </link>
159
+ <joint name="wrist_2_joint" type="revolute">
160
+ <parent link="wrist_1_link"/>
161
+ <child link="wrist_2_link"/>
162
+ <origin xyz="0.10 0 0" rpy="0 0 0"/>
163
+ <axis xyz="0 0 1"/>
164
+ <limit lower="-3.14159" upper="3.14159" velocity="2.0" effort="15.0"/>
165
+ </joint>
166
+
167
+ <!-- ============================================================
168
+ wrist_3_link (rotated around Y)
169
+ ============================================================ -->
170
+ <link name="wrist_3_link">
171
+ <visual>
172
+ <origin xyz="0.03 0 0" rpy="0 1.5707963 0"/>
173
+ <geometry><cylinder radius="0.026" length="0.06"/></geometry>
174
+ <material name="agros_blue"/>
175
+ </visual>
176
+ <inertial>
177
+ <mass value="0.4"/>
178
+ <inertia ixx="0.0004" iyy="0.0004" izz="0.0004" ixy="0" ixz="0" iyz="0"/>
179
+ </inertial>
180
+ </link>
181
+ <joint name="wrist_3_joint" type="revolute">
182
+ <parent link="wrist_2_link"/>
183
+ <child link="wrist_3_link"/>
184
+ <origin xyz="0 0 0.08" rpy="0 0 0"/>
185
+ <axis xyz="0 1 0"/>
186
+ <limit lower="-3.14159" upper="3.14159" velocity="2.0" effort="10.0"/>
187
+ </joint>
188
+
189
+ <!-- ============================================================
190
+ tool0 (end-effector frame). Tipped with a small red sphere so
191
+ the user can see "this is what an IK solver would target."
192
+ ============================================================ -->
193
+ <link name="tool0">
194
+ <visual>
195
+ <geometry><sphere radius="0.015"/></geometry>
196
+ <material name="agros_red"/>
197
+ </visual>
198
+ </link>
199
+ <joint name="tool0_joint" type="fixed">
200
+ <parent link="wrist_3_link"/>
201
+ <child link="tool0"/>
202
+ <origin xyz="0.06 0 0" rpy="0 0 0"/>
203
+ </joint>
204
+
205
+ </robot>
@@ -13,7 +13,7 @@
13
13
  * Standard physics + sensors + ros_gz system plugins so the AMR's depth
14
14
  camera / IMU / lidar publish on Gazebo topics that the bridge picks up
15
15
  -->
16
- <sdf version="1.10">
16
+ <sdf version="1.9">
17
17
  <world name="agenticros_indoor">
18
18
 
19
19
  <!-- ====== System plugins ====== -->