Skip to content

Commit 62da60a

Browse files
tpoignonecmergify[bot]
authored andcommitted
improve docs (#40)
* fix rules' flags * add basic VIC controller doc (cherry picked from commit 3bd70c6)
1 parent 61383f6 commit 62da60a

File tree

4 files changed

+86
-2
lines changed

4 files changed

+86
-2
lines changed

README.md

+84-2
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ Set of cartesian controllers for ros2_control
88

99

1010

11-
### Installation of the package
11+
# Installation of the package
1212

1313
```bash
1414
# Create a ros2 workspace with a source dir inside
@@ -40,7 +40,89 @@ colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --symlink-install
4040
source install/setup.bash
4141
```
4242

43+
## Code organization
44+
45+
### Overview
46+
47+
The following diagram describes the relation between packages:
48+
![UML class diagram](./cartesian_vic_controller/doc/UML_cartesian_vic_controllers.drawio.png)
49+
Note that this class diagram is NOT comprehensive and only features the main relations.
50+
51+
The main core ROS dependencies are `ros_control`, `generate_parameters_library`, `kinematics__interface`.
52+
The VIC controller makes use of the [dynamics_interface](https://github.com/tpoignonec/dynamics_interface) package for dynamic model access (based on kinematics_interface).
53+
54+
Additionally, the servo-based VIC implementation naturally requires the `moveit2` stack, including the latest `moveit_servo` package.
55+
56+
__Packages:__
57+
- `cartesian_control_msgs`: definition of main messages for VIC controllers state and references. Additionally, messages representing the Cartesian state of a manipulator robot are defined here.
58+
- `cartesian_state_broadcaster`: simple controller to broadcast the cartesian state (pose + velocity + force).
59+
- `cartesian_vic_controller`: main repos, see following section.
60+
- `cartesian_vic_teleop_controller`: extension of `cartesian_vic_controller` to bilateral VIC-based teleoperation.
61+
- `cartesian_vic_servo`: alternative implementation for VIC (admittance controller only) using MoveIt2 servo as underlying Cartesian velocity controller.
62+
63+
### Cartesian VIC controller
64+
65+
This is the main package that defines the control logic and the default VIC controller (based on ros-control).
66+
As visible in the diagram class diagram, the main control logic (see details in [cartesian_vic_controller/README.md](./cartesian_vic_controller/README.md)) is provided by the `CartesianVicRule` class.
67+
68+
```mermaid
69+
classDiagram
70+
note for VicRule "Pluginlib plugin"
71+
CartesianVicRule <|-- VicRuleImpl
72+
class CartesianVicRule{
73+
+ init()*
74+
+ configure()*
75+
+ update()
76+
+ reset()*
77+
+ init_reference_frame_trajectory()
78+
+ update_compliant_frame_trajectory()
79+
+ controller_state_to_msg()
80+
# compute_controls()*
81+
}
82+
class VicRuleImpl{
83+
+ init()*
84+
+ configure()*
85+
+ reset()*
86+
# compute_controls()*
87+
}
88+
```
89+
90+
The base class `CartesianVicRule` provide the logic for robot state processing and packaging (see `VicInputData` class).
91+
It is also responsible for managing robot kinematic / dynamics and measurement filtering.
92+
The `update()` function inernally calls the `compute_controls()`, a pure virtual function that has to be provided by actual VIC implementations.
93+
94+
Each rule inherits from `CartesianVicRule` and provide an implementation of `compute_controls`, whose signature is as follows:
95+
96+
```cpp
97+
bool CartesianVicRule::compute_controls(
98+
double dt /*period in seconds*/,
99+
const VicInputData & vic_input_data,
100+
VicCommandData & vic_command_data);
101+
```
102+
103+
The implementation compute VIC controls from the `VicInputData` and returns commands in the form of a `VicCommandData` object. For instance, if the implementation is based on position control (e.g., admittance control) the following is valid:
104+
105+
```cpp
106+
// Set position reference
107+
vic_command_data.joint_command_position = <...>;
108+
109+
// Set flags for available commands
110+
// - Cartesian space
111+
vic_command_data.has_twist_command = false;
112+
// - joint space
113+
vic_command_data.has_position_command = true;
114+
vic_command_data.has_velocity_command = false;
115+
vic_command_data.has_acceleration_command = false;
116+
vic_command_data.has_effort_command = false;
117+
```
118+
119+
__Provided VIC rule implementations:__
120+
121+
- `VanillaCartesianAdmittanceRule`: a basic admittance control law that returns position and velocity (__recommended!__) commands.
122+
- `VanillaCartesianImpedanceRule`: a basic impedance control law that returns torque (i.e., `EFFORT`) commands.
123+
- `TwistCmdCartesianAdmittanceRule`: Same as `VanillaCartesianAdmittanceRule`, but the inverse kinematics is not handled.
124+
Note: this plugin is not compatible with the nominal controller, it is designed for `cartesian_vic_servo`.
43125

44-
### Examples
126+
## Examples
45127

46128
See the repos [ICube-Robotics/cartesian_controllers_ros2_examples](https://github.com/ICube-Robotics/cartesian_controllers_ros2_examples).
Loading

cartesian_vic_controller/src/rules/vanilla_cartesian_admittance_rule.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -423,6 +423,7 @@ bool VanillaCartesianAdmittanceRule::compute_controls(
423423
vic_command_data.joint_command_velocity * dt;
424424

425425
// Set flags for available commands
426+
vic_command_data.has_twist_command = false;
426427
vic_command_data.has_position_command = true;
427428
vic_command_data.has_velocity_command = true;
428429
vic_command_data.has_acceleration_command = false;

cartesian_vic_controller/src/rules/vanilla_cartesian_impedance_rule.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -360,6 +360,7 @@ bool VanillaCartesianImpedanceRule::compute_controls(
360360

361361
// Set flags for available commands
362362
// ------------------------------------------------
363+
vic_command_data.has_twist_command = false;
363364
vic_command_data.has_position_command = false;
364365
vic_command_data.has_velocity_command = false;
365366
vic_command_data.has_acceleration_command = true;

0 commit comments

Comments
 (0)