Skip to content

Commit 61695cb

Browse files
author
--global
committed
Add tricycle robot setup example and lifecycle diagram images
1 parent 1c3fd74 commit 61695cb

File tree

4 files changed

+494
-54
lines changed

4 files changed

+494
-54
lines changed

workshop/source/_source/control/05_Example.md

Lines changed: 22 additions & 54 deletions
Original file line numberDiff line numberDiff line change
@@ -56,14 +56,26 @@ ros2 topic echo /controller_manager/introspection_data/full
5656
Focus on `wbot_base_control.nonlimited` and `wbot_base_control.limited` as you drive to see command limiting in action.
5757

5858
## 4. Visualize introspection values in PlotJuggler
59+
Introspection of the ros2_control setup
60+
With the integration of the pal_statistics package, the controller_manager node publishes the registered variables within the same process to the ~/introspection_data topics. By default, all State and Command interfaces in the controller_manager are registered when they are added, and are unregistered when they are removed from the ResourceManager. The state of the all the registered entities are published at the end of every update cycle of the controller_manager. For instance, In a complete synchronous ros2_control setup (with synchronous controllers and hardware components), this data in the Command interface is the command used by the hardware components to command the hardware.
5961

60-
```sh
62+
What gets published (message types):
63+
- `/controller_manager/introspection_data/full` (`pal_statistics_msgs/msg/StatisticsValues`): publishes the full introspection data, so names and values travel together for quick CLI inspection.
64+
- `/controller_manager/introspection_data/names` (`pal_statistics_msgs/msg/StatisticsNames`): publishes the names of the registered variables whenever interfaces are registered or removed.
65+
- `/controller_manager/introspection_data/values` (`pal_statistics_msgs/msg/StatisticsValues`): publishes only the changing values every update cycle when a subscriber is present (ideal for PlotJuggler).
66+
67+
All the registered variables are still published over the 3 topics: ~/introspection_data/full, ~/introspection_data/names, and ~/introspection_data/values. The topics ~/introspection_data/full and ~/introspection_data/values are always published on every update cycle asynchronously, provided that there is at least one subscriber to these topics.
68+
69+
You can wire these directly into a visualization:
70+
- The topic ~/introspection_data/full can be used to integrate with your custom visualization tools or to track the variables from the command line.
71+
- The topic ~/introspection_data/names and ~/introspection_data/values are to be used for visualization tools like PlotJuggler or RQT plot to visualize the data.
72+
- In PlotJuggler, add the `/controller_manager/introspection_data/values` stream and expand the interface names to plot wheel commands, joint states, or controller timings in real time.
73+
74+
```bash
75+
sudo apt install ros-jazzy-plotjuggler
6176
ros2 run plotjuggler plotjuggler
6277
```
63-
64-
1. Start the ROS 2 subscriber.
65-
2. Add `/controller_manager/introspection_data/values` as a topic.
66-
3. Plot `wbot_base_control.nonlimited` and `wbot_base_control.limited`; they publish at 100 Hz.
78+
![Plotjuggler](plotjuggler_select_topics.png)
6779

6880
## 5. ros2_control configuration reference
6981

@@ -85,14 +97,6 @@ Hardware macro snippet:
8597
<param name="state_following_offset">0.0</param>
8698
<param name="calculate_dynamics">true</param>
8799
</xacro:if>
88-
<xacro:unless value="${mock_hardware}">
89-
<plugin>joint_state_topic_hardware_interface/JointStateTopicSystem</plugin>
90-
<param name="joint_commands_topic">${joint_command_topic}</param>
91-
<param name="joint_states_topic">${joint_states_topic}</param>
92-
<param name="sum_wrapped_joint_states">true</param>
93-
<param name="trigger_joint_command_threshold">-1</param>
94-
<param name="enable_command_limiting">${enable_command_limiting}</param>
95-
</xacro:unless>
96100
</hardware>
97101
<joint name="wbot_wheel_left_joint">
98102
<command_interface name="velocity">
@@ -143,27 +147,7 @@ diff_drive_base_controller:
143147
base_frame_id: wbot_base_footprint
144148
pose_covariance_diagonal: [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
145149
twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]
146-
open_loop: false
147-
position_feedback: true
148-
enable_odom_tf: true
149-
cmd_vel_timeout: 0.5
150-
linear.x.has_velocity_limits: true
151-
linear.x.has_acceleration_limits: true
152-
linear.x.has_jerk_limits: false
153-
linear.x.max_velocity: 1.0
154-
linear.x.min_velocity: -1.0
155-
linear.x.max_acceleration: 2.5
156-
linear.x.max_jerk: 0.0
157-
linear.x.min_jerk: 0.0
158-
angular.z.has_velocity_limits: true
159-
angular.z.has_acceleration_limits: true
160-
angular.z.has_jerk_limits: false
161-
angular.z.max_velocity: 2.0
162-
angular.z.min_velocity: -2.0
163-
angular.z.max_acceleration: 6.2
164-
angular.z.min_acceleration: -6.2
165-
angular.z.max_jerk: 0.0
166-
angular.z.min_jerk: 0.0
150+
...
167151

168152
joint_trajectory_controller:
169153
ros__parameters:
@@ -181,25 +165,7 @@ joint_trajectory_controller:
181165
- velocity
182166
state_publish_rate: 0.0
183167
action_monitor_rate: 20.0
184-
allow_partial_joints_goal: false
185-
open_loop_control: false
186-
allow_nonzero_velocity_at_trajectory_end: true
187-
interpolation_method: splines
188-
constraints:
189-
stopped_velocity_tolerance: 0.01
190-
goal_time: 0.0
191-
joint_1:
192-
goal: 0.001
193-
joint_2:
194-
goal: 0.001
195-
joint_3:
196-
goal: 0.001
197-
joint_4:
198-
goal: 0.001
199-
joint_5:
200-
goal: 0.001
201-
joint_6:
202-
goal: 0.001
168+
...
203169

204170
gripper_controller:
205171
ros__parameters:
@@ -301,11 +267,13 @@ ros2 topic pub /joint_trajectory_controller/joint_trajectory trajectory_msgs/Joi
301267
### Gripper (GripperActionController)
302268

303269
```sh
270+
# open
304271
ros2 action send_goal /gripper_controller/gripper_cmd control_msgs/action/ParallelGripperCommand "{command: {name: [wbot_arm_gripper_joint], position: [0.03]}}"
272+
#close
305273
ros2 action send_goal /gripper_controller/gripper_cmd control_msgs/action/ParallelGripperCommand "{command: {name: [wbot_arm_gripper_joint], position: [0.0]}}"
306274
```
307275

308276
![WBot Gripper](wbot_gripper.gif)
309277

310278
### References
311-
- [ROSCon 2025 Control Workshop](https://github.com/ros-controls/roscon2025_control_workshop)
279+
- [ROSCon 2025 Control Workshop](https://github.com/ros-controls/roscon2025_control_workshop)

0 commit comments

Comments
 (0)